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 #ifndef FLIR_BOSON_USB_BOSONCAMERA_H
00022 #define FLIR_BOSON_USB_BOSONCAMERA_H
00023
00024
00025 #include <string>
00026
00027
00028 #include <fcntl.h>
00029 #include <unistd.h>
00030 #include <sys/ioctl.h>
00031 #include <asm/types.h>
00032 #include <sys/mman.h>
00033 #include <sys/types.h>
00034 #include <sys/stat.h>
00035 #include <linux/videodev2.h>
00036
00037
00038 #include <opencv2/opencv.hpp>
00039
00040
00041 #include <ros/ros.h>
00042 #include <nodelet/nodelet.h>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <image_transport/image_transport.h>
00045 #include <camera_info_manager/camera_info_manager.h>
00046
00047 #include <sensor_msgs/CameraInfo.h>
00048 #include <sensor_msgs/Image.h>
00049
00050 namespace flir_boson_usb
00051 {
00052
00053 enum Encoding
00054 {
00055 YUV = 0,
00056 RAW16 = 1
00057 };
00058
00059 enum SensorTypes
00060 {
00061 Boson320,
00062 Boson640
00063 };
00064
00065 class BosonCamera : public nodelet::Nodelet
00066 {
00067 public:
00068 BosonCamera();
00069 ~BosonCamera();
00070
00071 private:
00072 virtual void onInit();
00073 void agcBasicLinear(const cv::Mat& input_16,
00074 cv::Mat* output_8,
00075 const int& height,
00076 const int& width);
00077 bool openCamera();
00078 bool closeCamera();
00079 void captureAndPublish(const ros::TimerEvent& evt);
00080
00081 ros::NodeHandle nh, pnh;
00082 std::shared_ptr<camera_info_manager::CameraInfoManager> camera_info;
00083 std::shared_ptr<image_transport::ImageTransport> it;
00084 image_transport::CameraPublisher image_pub;
00085 cv_bridge::CvImage cv_img;
00086 sensor_msgs::ImagePtr pub_image;
00087 ros::Timer capture_timer;
00088 int32_t width, height;
00089 int32_t fd;
00090 int32_t i;
00091 struct v4l2_capability cap;
00092 int32_t frame = 0;
00093 int8_t thermal_sensor_name[20];
00094 struct v4l2_buffer bufferinfo;
00095 void* buffer_start;
00096
00097 cv::Mat thermal16, thermal16_linear, thermal16_linear_zoom,
00098 thermal_rgb_zoom, thermal_luma, thermal_rgb;
00099
00100
00101 std::string frame_id, dev_path, camera_info_url,
00102 video_mode_str, sensor_type_str;
00103 float frame_rate;
00104 Encoding video_mode;
00105 bool zoom_enable;
00106 SensorTypes sensor_type;
00107 };
00108
00109 }
00110
00111 #endif // FLIR_BOSON_USB_BOSONCAMERA_H