vimba_ros.h
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 #ifndef VIMBA_ROS_H
00034 #define VIMBA_ROS_H
00035 
00036 #include <VimbaCPP/Include/VimbaCPP.h>
00037 
00038 #include <avt_vimba_camera/AvtVimbaCameraConfig.h>
00039 #include <avt_vimba_camera/frame_observer.h>
00040 
00041 #include <ros/ros.h>
00042 #include <driver_base/SensorLevels.h>
00043 #include <sensor_msgs/Image.h>
00044 #include <sensor_msgs/CameraInfo.h>
00045 #include <sensor_msgs/SetCameraInfo.h>
00046 #include <camera_info_manager/camera_info_manager.h>
00047 #include <image_transport/image_transport.h>
00048 #include <dynamic_reconfigure/server.h>
00049 #include <polled_camera/publication_server.h>
00050 
00051 #include <string>
00052 #include <map>
00053 
00054 using AVT::VmbAPI::VimbaSystem;
00055 using AVT::VmbAPI::CameraPtr;
00056 using AVT::VmbAPI::FramePtr;
00057 using AVT::VmbAPI::IFrameObserverPtr;
00058 
00059 namespace avt_vimba_camera {
00060 
00061 enum FrameStartTriggerMode {
00062   Freerun,
00063   FixedRate,
00064   Software,
00065   SyncIn1,
00066   SyncIn2,
00067   SyncIn3,
00068   SyncIn4
00069 };
00070 
00071 enum AcquisitionMode {
00072   Continuous,
00073   SingleFrame,
00074   MultiFrame,
00075   Recorder
00076 };
00077 
00078 enum PixelFormatMode {
00079   Mono8,
00080   Mono12,
00081   Mono12Packed,
00082   BayerRG8,
00083   BayerRG12Packed,
00084   BayerRG12,
00085   RGB8Packed,
00086   BGR8Packed
00087 };
00088 
00089 enum AutoSettingMode {
00090   Off,
00091   Once,
00092   Auto
00093 };
00094 
00095 class VimbaROS {
00096   public:
00097     VimbaROS(ros::NodeHandle nh, ros::NodeHandle nhp);
00098     int getWidth();
00099     int getHeight();
00100     int getMaxWidth();
00101     int getMaxHeight();
00102 
00103   private:
00104     // true if camera is started
00105     bool running_;
00106     bool first_run_;
00107 
00108     // ROS Nodehandles
00109     ros::NodeHandle nh_;
00110     ros::NodeHandle nhp_;
00111     // ROS image transport
00112     image_transport::ImageTransport it_;
00113     // ROS Camera publisher
00114     image_transport::CameraPublisher streaming_pub_;
00115     // ROS Service to get images
00116     polled_camera::PublicationServer poll_srv_;
00117     // Subscriber for input trigger time
00118     ros::Subscriber trigger_sub_;
00119 
00120     // ROS params
00121     int num_frames_;
00122     std::string frame_id_;
00123     std::string trigger_mode_;
00124     int trigger_mode_int_;
00125 
00126     // ROS messages
00127     typedef driver_base::SensorLevels Levels;
00128     sensor_msgs::CameraInfo cam_info_;
00129     boost::shared_ptr<camera_info_manager::CameraInfoManager> cinfo_;
00130 
00131     // Dynamic reconfigure
00132     typedef avt_vimba_camera::AvtVimbaCameraConfig Config;
00133     typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00134     ReconfigureServer reconfigure_server_;
00135 
00136     // Camera configuration
00137     Config camera_config_;
00138 
00139     // Vimba singleton
00140     VimbaSystem& vimba_system_;
00141     // IFrame Observer
00142     FrameObserver* vimba_frame_observer_ptr_;
00143     // The currently streaming camera
00144     CameraPtr vimba_camera_ptr_;
00145     // Current frame
00146     FramePtr vimba_frame_ptr_;
00147     // The max width
00148     VmbInt64_t vimba_camera_max_width_;
00149     // The max height
00150     VmbInt64_t vimba_camera_max_height_;
00151     // A readable value for every Vimba error code
00152     std::map<VmbErrorType, std::string> vimba_error_code_to_message_;
00153 
00154     /*************/
00155     /* FUNCTIONS */
00156     /*************/
00157 
00158     template<typename T> bool getFeatureValue(const std::string& feature_str, T& val);
00159     bool getFeatureValue(const std::string& feature_str, std::string& val);
00160     template<typename T> bool setFeatureValue(const std::string& feature_str, const T& val);
00161     bool runCommand(const std::string& command_str);
00162 
00163     void updateAcquisitionConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00164     void updateExposureConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00165     void updateGainConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00166     void updateWhiteBalanceConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00167     void updateImageModeConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00168     void updateROIConfig(Config& config, FeaturePtrVector feature_ptr_vec);
00169     void updateBandwidthConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00170     void updatePixelFormatConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00171     void updateGPIOConfig(const Config& config, FeaturePtrVector feature_ptr_vec);
00172 
00173 
00174     void start(Config& config);
00175     void stop();
00176     void frameCallback(const FramePtr vimba_frame_ptr);
00177     void pollCallback(polled_camera::GetPolledImage::Request& req,
00178                       polled_camera::GetPolledImage::Response& rsp,
00179                       sensor_msgs::Image& image,
00180                       sensor_msgs::CameraInfo& info);
00181     bool frameToImage(const FramePtr vimba_frame_ptr, sensor_msgs::Image& image);
00182 
00183 
00184     // Configure camera info
00185     void updateCameraInfo(const Config& config);
00186     // Dynamic Reconfigure Callback
00187     void configure(Config& newconfig, uint32_t level);
00188 
00189     // Init function to setup AVT Vimba SDK
00190     void initApi(void);
00191     // Translates Vimba error codes to readable error messages
00192     std::string errorCodeToMessage(VmbErrorType eErr);
00193     // Translates Vimba access mode codes to readable messages
00194     std::string accessModeToString(VmbAccessModeType modeType);
00195     // Parser of Vimba Interface Type
00196     std::string interfaceToString(VmbInterfaceType interfaceType);
00197     // Parser of trigger mode to non-readable integer
00198     int getTriggerModeInt(std::string mode);
00199     // Open the required camera
00200     CameraPtr openCamera(std::string id);
00201     // Dummy function to print all features of a camera
00202     void printAllCameraFeatures(CameraPtr camera);
00203     // Dummy function to list all cameras
00204     void listAvailableCameras(void);
00205 };
00206 }
00207 
00208 #endif


avt_vimba_camera
Author(s): Miquel Massot , Allied Vision Technologies
autogenerated on Thu Aug 27 2015 12:29:49