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_DRIVER_H 00014 #define XIMEA_CAMERA_XIMEA_DRIVER_H 00015 00016 // Sample for XIMEA Software Package V2.57 00017 #include <m3api/xiApi.h> 00018 #include <ros/ros.h> 00019 #include <image_transport/image_transport.h> 00020 #include <image_transport/publisher.h> 00021 #include <sensor_msgs/Image.h> 00022 #include <sensor_msgs/CameraInfo.h> 00023 #include <std_msgs/UInt8.h> 00024 #include <camera_info_manager/camera_info_manager.h> 00025 #include <stdio.h> 00026 #include <stdlib.h> 00027 #include <iostream> 00028 #include <string> 00029 #include <fstream> 00030 #include <yaml-cpp/yaml.h> 00031 00032 class ximea_driver 00033 { 00034 public: 00035 explicit ximea_driver(int serial_no = 0 , std::string cam_name = ""); // if no serial no is specified select the first cam on the bus 00036 explicit ximea_driver(std::string file_name); 00037 00038 int readParamsFromFile(std::string file_name); 00039 void applyParameters(); 00040 void errorHandling(XI_RETURN ret, std::string message); 00041 void enableTrigger(unsigned char trigger_mode); // 0 none, 1 soft_trigger, 2 hard_trigger_rising edge (unsupported) 00042 void limitBandwidth(int mbps); 00043 void openDevice(); 00044 void closeDevice(); 00045 void startAcquisition(); 00046 void stopAcquisition(); 00047 void acquireImage(); 00048 void triggerDevice(); 00049 int getSerialNo() const 00050 { 00051 return serial_no_; 00052 } 00053 virtual void setImageDataFormat(std::string s); // this is virtual because the ros class needs to do a bit more work to publish the right image 00054 void setROI(int rect_left, int rect_top, int rect_width, int rect_height); 00055 void setExposure(int time); 00056 void setAutoExposure(int auto_exposure); 00057 void setAutoExposureLimit(int ae_limit); 00058 void setAutoGainLimit(int ag_limit); 00059 void setAutoExposurePriority(float exp_priority); 00060 bool hasValidHandle() 00061 { 00062 return xiH_ == NULL ? false : true; 00063 } 00064 const XI_IMG& getImage()const 00065 { 00066 return image_; 00067 } 00068 00069 protected: 00070 void assignDefaultValues(); 00071 00072 // variables for ximea api internals 00073 std::string cam_name_; 00074 int serial_no_; 00075 std::string frame_id_; 00076 int cams_on_bus_; 00077 int bandwidth_safety_margin_; 00078 int frame_rate_; 00079 int bandwidth_; 00080 int exposure_time_; 00081 int auto_exposure_; 00082 int auto_exposure_limit_; 00083 int auto_gain_limit_; 00084 float auto_exposure_priority_; 00085 bool binning_enabled_; 00086 int downsample_factor_; 00087 int rect_left_; 00088 int rect_top_; 00089 int rect_width_; 00090 int rect_height_; 00091 bool acquisition_active_; 00092 std::string image_data_format_; // One of XI_MONO8, XI_RGB24, XI_RGB32, XI_RAW 00093 std::string yaml_url_; 00094 HANDLE xiH_; 00095 XI_IMG image_; 00096 int image_capture_timeout_; // max amount of time to wait for an image to come in 00097 unsigned char trigger_mode_; 00098 }; 00099 00100 #endif // XIMEA_CAMERA_XIMEA_DRIVER_H