ximea_ros_cluster.h
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 #ifndef XIMEA_CAMERA_XIMEA_ROS_CLUSTER_H
00014 #define XIMEA_CAMERA_XIMEA_ROS_CLUSTER_H
00015 
00016 #include <ximea_camera/ximea_ros_driver.h>
00017 #include <boost/thread.hpp>
00018 #include <string>
00019 #include <vector>
00020 
00021 class ximea_ros_cluster
00022 {
00023 public:
00024   explicit ximea_ros_cluster(int num_cams);
00025   explicit ximea_ros_cluster(std::vector < std::string > filenames);
00026   void add_camera(ximea_ros_driver xd);
00027   void remove_camera(int serial_no);
00028 
00029   // cluster functions
00030   void clusterInit();
00031   void clusterAcquire();
00032   void clusterPublishImages();
00033   void clusterPublishCamInfo();
00034   void clusterPublishImageAndCamInfo();
00035   void clusterEnd();
00036   bool isDeviceOpen()
00037   {
00038     return devices_open_;
00039   }
00040 
00041   // individual camera functions (encapsulated for thread security)
00042   void setExposure(int serial_no, int time);
00043   void setImageDataFormat(int serial_no, std::string s);
00044   void setROI(int serial_no, int l, int t, int w, int h);
00045 
00046 private:
00047   std::vector<ximea_ros_driver> cams_;
00048   std::vector<boost::thread*> threads_;
00049   bool devices_open_;
00050   int num_cams_;
00051   int getCameraIndex(int serial_no);  // this is private so that no one tries to be smart and open/close our cameras externally, in which case we cannot manage
00052   const int USB_BUS_SAFETY_MARGIN;
00053   const int USB3_BANDWIDTH;
00054   bool fixed_init_;
00055 };
00056 
00057 #endif  // XIMEA_CAMERA_XIMEA_ROS_CLUSTER_H


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