bool ToFCameraPMDController::CloseCameraConnection() { m_PMDRes = pmdClose(m_PMDHandle); m_ConnectionCheck = ErrorText(m_PMDRes); m_PMDHandle = 0; return m_ConnectionCheck; }
/** * * @brief Main function * * @param [in] int * @param [in] char * * */ int main(int argc, char *argv[]) { ROS_INFO("Starting argos3d_p100 ros..."); ros::init (argc, argv, "argos3d_p100"); ros::NodeHandle nh; dynamic_reconfigure::Server<argos3d_p100::argos3d_p100Config> srv; dynamic_reconfigure::Server<argos3d_p100::argos3d_p100Config>::CallbackType f; f = boost::bind(&callback, _1, _2); if(initialize(argc, argv,nh)){ first = true; srv.setCallback(f); first = false; ROS_INFO("Initalized Camera... Reading Data"); ros::Rate loop_rate(10); while (nh.ok() && dataPublished) { if(publishData()) dataPublished==true; ros::spinOnce (); loop_rate.sleep (); } } else { ROS_WARN("Cannot Initialize Camera. Check the parameters and try again!!"); return 0; } pmdClose (hnd); return 0; }
bool ToFCameraPMDMITKPlayerController::CloseCameraConnection() { if(m_MitkImage.IsNotNull()) { this->m_MitkImage->ReleaseData(); } this->m_PMDRes = pmdClose(m_PMDHandle); m_ConnectionCheck = ErrorText(this->m_PMDRes); m_PMDHandle = 0; return m_ConnectionCheck; }
int o3d3xx_sample_imager_settings_function(void) { PMDHandle hnd = 0; std::string command = ""; int res = 0; char err[256] = {0}; char response[SOURCE_CMD_BUFFER_LENGTH] = {0}; unsigned int integrationTime = 0; // connect to camera printf ("\n ====================O3D300 Sample Code for Imager Settings===================="); printf ("\n Connecting to camera: \n"); res = pmdOpen (&hnd, SOURCE_PLUGIN, SOURCE_PARAM, PROC_PLUGIN, PROC_PARAM); if (res != PMD_OK) { fprintf (stderr, "Could not connect: \n"); getchar(); return res; } // Change Exposure Mode to "moderate" printf ("\n -----------------------------------------------------------------------------"); printf ("\n--------------------Imager Settings Functionality-----------------------------"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Get Imager Setting Type\n"); command = "GetImagerSettingType"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not change exposure mode:\n%s\n", err); printf (" Press any key to continue...."); getchar(); } else { printf("Type: %s", response); printf ("\n DONE"); } printf ("\n -----------------------------------------------------------------------------"); printf ("\n Set Exposure Mode to 'moderate'\n"); command = "SetExposureMode 1"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not change exposure mode:\n%s\n", err); printf (" Press any key to continue...."); getchar(); } else printf ("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Set unambiguous distance range to 'upto30m'\n"); command = "SetUnambiguousDistanceRange 1"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not change unambiguous distance range:\n%s\n", err); printf (" Press any key to continue...."); getchar(); } else printf ("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Get Imager Setting Type\n"); command = "GetImagerSettingType"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not change exposure mode:\n%s\n", err); printf (" Press any key to continue...."); getchar(); } else { printf("Type: %s", response); printf ("\n DONE"); } // Get the current Exposure Time and Exposure Time Ratio printf ("\n -----------------------------------------------------------------------------"); printf ("\n Get Integration Time 1\n"); // Call pmdGetIntegrationTime with index 0 to get exposure time res = pmdGetIntegrationTime (hnd, &integrationTime , 0); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not get integration time 1:\n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } else { printf("Integration time 1 = %d usec", integrationTime); printf ("\n DONE"); } printf ("\n -----------------------------------------------------------------------------"); printf ("\n Get Integration Time Ratio\n"); command = "GetExposureTimeRatio"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not get integration time ratio:\n%s\n", err); getchar(); } else { int integrationTimeRatio = atoi( response ); printf("Integration time Ratio = %d", integrationTimeRatio); printf ("\n DONE"); } // Change Exposure Time and Exposure Time Ratio printf ("\n -----------------------------------------------------------------------------"); printf ("\n Setting exposureTime to 1000 usec \n"); // Call pmdSetIntegrationTime with index 0 to set exposure time res = pmdSetIntegrationTime (hnd, 0 , 1000); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, "Could not set the exposure time: \n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } else printf("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Setting exposureTimeRatio to 50 \n"); command = "SetExposureTimeRatio 50"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, "Could not set the exposure time ratio: \n%s\n", err); getchar(); } else printf("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Getting Exposure Time List \n"); command = "GetExposureTimeList"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, "Could not get the exposure time list: \n%s\n", err); getchar(); } else { printf("Exposure Time List = %s", response); printf("\n DONE"); } // Optimizing exposure time : Setting integration time 10,000 usec before optimizing // exposure time to see the effect of optimizing functionality printf ("\n -----------------------------------------------------------------------------"); printf ("\n Set Exposure Mode to 'low'\n"); command = "SetExposureMode 0"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not change exposure mode:\n%s\n", err); printf (" Press any key to continue...."); getchar(); } else printf ("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Setting integrationTime to 10,000 usec \n"); res = pmdSetIntegrationTime (hnd, 0 , 10000); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, "Could not set the integration time: \n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } printf ("\n -----------------------------------------------------------------------------"); printf ("\n Call Optimize function\n"); command = "OptimizeExposureTime"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Error in Optimization Procedure:\n%s\n", err); printf (" Press any key to continue...."); getchar(); } else printf ("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Get Integration Time 1\n"); res = pmdGetIntegrationTime (hnd, &integrationTime , 0); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not get integration time 1:\n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } else { printf("Integration time 1 = %d usec", integrationTime); printf ("\n DONE"); } unsigned int modulationFrequencyChannel; printf ("\n -----------------------------------------------------------------------------"); printf ("\n Get Modulation Frequency Channel\n"); res = pmdGetModulationFrequency (hnd, &modulationFrequencyChannel, 0); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not get modulation frequency:\n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } else { printf("Modulation Frequency Channel = %d", modulationFrequencyChannel); printf ("\n DONE"); } modulationFrequencyChannel = 2; printf ("\n -----------------------------------------------------------------------------"); printf ("\n Set Modulation Frequency Channel to 2\n"); res = pmdSetModulationFrequency (hnd, 0, modulationFrequencyChannel); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not set modulation frequency:\n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } else printf ("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Get Modulation Frequency Channel\n"); res = pmdGetModulationFrequency (hnd, &modulationFrequencyChannel, 0); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not get modulation frequency:\n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } else { printf("Modulation Frequency Channel = %d", modulationFrequencyChannel); printf ("\n DONE"); } modulationFrequencyChannel = 1; printf ("\n -----------------------------------------------------------------------------"); printf ("\n Set Modulation Frequency Channel to 2\n"); res = pmdSetModulationFrequency (hnd, 0, modulationFrequencyChannel); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not set modulation frequency:\n%s\n", err); pmdClose (hnd); printf("Camera Connection Closed. \n"); printf ("Exiting application after key press...."); getchar(); return res; } else printf ("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n---------------Source Commands: Invalid Imager Settings Parameters------------"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Setting Exposure Mode with invalid arguments: ""SetExposureMode 5""\n"); command = "SetExposureMode 5"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { printf (" Result: \n"); pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not set exposure mode:\n%s\n", err); } else printf ("\n DONE"); printf ("\n -----------------------------------------------------------------------------"); printf ("\n Setting Unambiguous Range with invalid arguments: ""SetUnambiguousDistanceRange 5""\n"); command = "SetUnambiguousDistanceRange 5"; res = pmdSourceCommand (hnd, response, SOURCE_CMD_BUFFER_LENGTH, command.c_str()); if (res != PMD_OK) { printf (" Result: \n"); pmdGetLastError (hnd, err, 128); fprintf (stderr, " Could not set unambiguous distance range:\n%s\n", err); } else printf ("\n DONE"); // Closing the connection. res = pmdClose (hnd); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); fprintf (stderr, "Could not close the connection %s\n", err); return res; } printf ("\n Camera closed Successfully"); printf ("\n ================================================================================"); return PMD_OK; }
/** * * @brief Publish the data based on set up parameters. * */ int publishData() { /* * Update Camera settings */ res = pmdUpdate (hnd); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); ROS_ERROR_STREAM("Could transfer data: " << err); pmdClose (hnd); return 0; } /* * Obtain PointClouds */ if (!cartesianDist) cartesianDist = new float [noOfRows * noOfColumns * 3]; res = pmdGet3DCoordinates (hnd, cartesianDist, noOfColumns * noOfRows * 3 * sizeof (float)); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); ROS_ERROR_STREAM("Could get cartesian coordinates: " << err); pmdClose (hnd); return 0; } /* * Obtain Amplitude Values */ if (!amplitudes) amplitudes = new float [noOfRows * noOfColumns]; res = pmdGetAmplitudes (hnd, amplitudes, noOfRows * noOfColumns * sizeof (float)); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); ROS_ERROR_STREAM("Could get amplitude values: " << err); pmdClose (hnd); return 1; } /* * Creating the pointcloud */ // Fill in the cloud data PointCloud::Ptr msg_non_filtered (new PointCloud); msg_non_filtered->header.frame_id = "tf_argos3d"; msg_non_filtered->height = 1; msg_non_filtered->width = noOfRows*noOfColumns; PointCloud::Ptr msg_filtered (new PointCloud); msg_filtered->header.frame_id = "tf_argos3d"; msg_filtered->width = 1; msg_filtered->height = noOfColumns*noOfRows; msg_filtered->is_dense = false; //msg_filtered->points.resize (noOfRows*noOfColumns); int countWidth=0; for (size_t i = 0; i < noOfRows*noOfColumns; ++i) { pcl::PointXYZI temp_point; temp_point.x = cartesianDist[(i*3) + 0]*flip_x; temp_point.y = cartesianDist[(i*3) + 1]*flip_y; temp_point.z = cartesianDist[(i*3) + 2]; temp_point.intensity = amplitudes[i]; if(AmplitudeFilterOn==true && amplitudes[i]>AmplitudeThreshold) { msg_filtered->points.push_back(temp_point); countWidth++; } msg_non_filtered->points.push_back(temp_point); } msg_filtered->height = countWidth; /* * Publishing the messages */ if(AmplitudeFilterOn){ #if ROS_VERSION > ROS_VERSION_COMBINED(1,9,49) msg_filtered->header.stamp = ros::Time::now().toNSec(); #else msg_filtered->header.stamp = ros::Time::now(); #endif pub_filtered.publish (msg_filtered); } #if ROS_VERSION > ROS_VERSION_COMBINED(1,9,49) msg_non_filtered->header.stamp = ros::Time::now().toNSec(); #else msg_non_filtered->header.stamp = ros::Time::now(); #endif pub_non_filtered.publish (msg_non_filtered); return 1; }
/** * * @brief Initialize the camera and initial parameter values. Returns 1 if properly initialized. * * @param [in] int * @param [in] argv * @param [in] ros::NodeHandle * */ int initialize(int argc, char *argv[],ros::NodeHandle nh){ /* * Inital Setup for parameters */ integrationTime = 1500; modulationFrequency = 30000000; frameRate = 40; bilateralFilter = false; flip_x = flip_y = 1; AmplitudeFilterOn = false; AmplitudeThreshold = 0; for( int i = 1; i < argc; i++) { // reading width if( std::string(argv[i]) == "-it" ) { if( sscanf(argv[++i], "%d", &integrationTime) != 1 || integrationTime < 100 || integrationTime > 2700 ) { ROS_WARN("*invalid integration time"); return help(); } } // reading heigth else if( std::string(argv[i]) == "-mf" ) { if( sscanf(argv[++i], "%d", &modulationFrequency) != 1 || modulationFrequency < 5000000 || modulationFrequency > 30000000 ) { ROS_WARN("*invalid modulation frequency"); return help(); } } if( std::string(argv[i]) == "-fr" ) { if( sscanf(argv[++i], "%d", &frameRate) != 1 || frameRate < 1 || frameRate > 40 ) { ROS_WARN("*invalid frame rate"); return help(); } } else if( std::string(argv[i]) == "-bf" ) { bilateralFilter = true; } else if( std::string(argv[i]) == "-flip_x" ) { flip_x = -1; } else if( std::string(argv[i]) == "-flip_y" ) { flip_y = -1; } // additional parameters else if( std::string(argv[i]) == "-af" ) { AmplitudeFilterOn = true; } else if( std::string(argv[i]) == "-at" ) { if( sscanf(argv[++i], "%f", &AmplitudeThreshold) != 1 || AmplitudeThreshold < 0 || AmplitudeThreshold > 2500 ) { ROS_WARN("*invalid amplitude threshold"); return help(); } } // print help else if( std::string(argv[i]) == "--help" ) { ROS_WARN_STREAM("arguments: " << argc << " which: " << argv[i]); return help(); } else if( argv[i][0] == '-' ) { ROS_WARN_STREAM("invalid option " << argv[i]); return help(); } } /* * Camera Initialization */ std::stringstream sourcePluginLocation, procPluginLocation; sourcePluginLocation.clear(); procPluginLocation.clear(); sourcePluginLocation << PMD_PLUGIN_DIR << "digicam"; procPluginLocation << PMD_PLUGIN_DIR << "digicamproc"; // If the camera is not connected at all, we will get an segmentation fault. res = pmdOpen (&hnd, sourcePluginLocation.str().c_str(), SOURCE_PARAM, procPluginLocation.str().c_str(), PROC_PARAM); if (res != PMD_OK) { pmdGetLastError (0, err, 128); ROS_ERROR_STREAM("Could not connect: " << err); return 0; } char result[128]; result[0] = 0; res = pmdSourceCommand(hnd, result, sizeof(result), "IsCalibrationDataLoaded"); if (res != PMD_OK) { pmdGetLastError (0, err, 128); ROS_ERROR_STREAM("Could not execute source command: " << err); pmdClose (hnd); return 0; } if (std::string(result) == "YES") ROS_INFO("Calibration file loaded."); else ROS_INFO("No calibration file found"); res = pmdUpdate (hnd); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); ROS_ERROR_STREAM("Could not transfer data: " << err); pmdClose (hnd); return 0; } PMDDataDescription dd; res = pmdGetSourceDataDescription (hnd, &dd); if (res != PMD_OK) { pmdGetLastError (hnd, err, 128); ROS_ERROR_STREAM("Could not get data description: " << err); pmdClose (hnd); return 0; } if (dd.subHeaderType != PMD_IMAGE_DATA) { ROS_ERROR_STREAM("Source data is not an image!\n"); pmdClose (hnd); return 0; } noOfRows = dd.img.numRows; noOfColumns = dd.img.numColumns; /* * ROS Node Initialization */ pub_non_filtered = nh.advertise<PointCloud> ("depth_non_filtered", 1); pub_filtered = nh.advertise<PointCloud> ("depth_filtered", 1); dataPublished=true; return 1; }