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 MONO_CAMERA_H 00034 #define MONO_CAMERA_H 00035 00036 #include <avt_vimba_camera/avt_vimba_camera.h> 00037 #include <avt_vimba_camera/AvtVimbaCameraConfig.h> 00038 #include <avt_vimba_camera/avt_vimba_api.h> 00039 00040 #include <ros/ros.h> 00041 #include <sensor_msgs/Image.h> 00042 #include <sensor_msgs/CameraInfo.h> 00043 #include <camera_info_manager/camera_info_manager.h> 00044 #include <image_transport/image_transport.h> 00045 #include <dynamic_reconfigure/server.h> 00046 00047 #include <string> 00048 00049 namespace avt_vimba_camera { 00050 class MonoCamera { 00051 public: 00052 MonoCamera(ros::NodeHandle nh, ros::NodeHandle nhp); 00053 ~MonoCamera(void); 00054 00055 private: 00056 AvtVimbaApi api_; 00057 AvtVimbaCamera cam_; 00058 00059 // diagnostic_updater::Updater updater_; 00060 // diagnostic_updater::TopicDiagnostic* pub_freq_; 00061 00062 ros::NodeHandle nh_; 00063 ros::NodeHandle nhp_; 00064 00065 std::string ip_; 00066 std::string guid_; 00067 std::string camera_info_url_; 00068 bool show_debug_prints_; 00069 00070 image_transport::ImageTransport it_; 00071 // ROS Camera publisher 00072 image_transport::CameraPublisher pub_; 00073 00074 00075 00076 // sensor_msgs::CameraInfo left_info_; 00077 boost::shared_ptr<camera_info_manager::CameraInfoManager> info_man_; 00078 00079 // Dynamic reconfigure 00080 typedef avt_vimba_camera::AvtVimbaCameraConfig Config; 00081 typedef dynamic_reconfigure::Server<Config> ReconfigureServer; 00082 ReconfigureServer reconfigure_server_; 00083 00084 // Camera configuration 00085 Config camera_config_; 00086 00087 void frameCallback(const FramePtr& vimba_frame_ptr); 00088 void configure(Config& newconfig, uint32_t level); 00089 void updateCameraInfo(const Config& config); 00090 }; 00091 } 00092 #endif