ximea.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002 
00003 Copyright 2015  Abdelhamid El-Bably (University of Waterloo)
00004                       [ahelbably@uwaterloo.ca]
00005                 Arun Das (University of Waterloo)
00006                       [adas@uwaterloo.ca]
00007                 Michael Tribou (University of Waterloo)
00008                       [mjtribou@uwaterloo.ca]
00009 
00010 All rights reserved.
00011 
00012 ********************************************************************************/
00013 
00014 #include <ximea_camera/ximea_ros_cluster.h>
00015 #include <string>
00016 #include <vector>
00017 
00018 int main(int argc, char ** argv)
00019 {
00020   ros::init(argc, argv, "ximea");
00021   ros::NodeHandle nh;
00022   ros::NodeHandle pnh("~");
00023   int frame_rate_;
00024   std::vector<std::string> file_names;
00025 
00026   pnh.param<int>("frame_rate", frame_rate_, 100);
00027   pnh.getParam("camera_param_file_paths", file_names);
00028   ros::Rate loop(frame_rate_);
00029 
00030   // check size of camera file
00031   if (file_names.size() == 0)
00032   {
00033     ROS_ERROR("ximea_driver: No camera files name specified. Please set 'camera_param_file_paths' parameter to camera yaml file locations in launch file");
00034     return 0;
00035   }
00036   else
00037   {
00038     for (unsigned int i = 0; i < file_names.size(); i++)
00039     {
00040       ROS_INFO_STREAM("loading camera parameter file: " << file_names[i] << std::endl);
00041     }
00042   }
00043 
00044   ximea_ros_cluster xd(file_names);
00045   xd.clusterInit();
00046   while (ros::ok())   // TODO: need to robustify against replugging and cntrlc
00047   {
00048     ros::spinOnce();
00049     xd.clusterAcquire();
00050     xd.clusterPublishImageAndCamInfo();
00051     loop.sleep();
00052   }
00053   xd.clusterEnd();
00054   return 1;
00055 }


ximea_camera
Author(s): Abdelhamid El-Bably, Arun Das, Michael Tribou
autogenerated on Thu Jun 6 2019 21:17:12