00001 #ifndef FOSCAM_DRIVER_H 00002 #define FOSCAM_DRIVER_H 00003 00004 // System includes. 00005 #include <math.h> 00006 #include <stdio.h> 00007 #include <stdlib.h> 00008 #include <string.h> 00009 #include <unistd.h> 00010 #include <errno.h> 00011 #include <iostream> 00012 00013 // OpenCV includes. 00014 #include <opencv2/opencv.hpp> 00015 00016 // ROS includes. 00017 #include <ros/ros.h> 00018 #include <ros/console.h> 00019 #include <ros/time.h> 00020 #include <camera_info_manager/camera_info_manager.h> 00021 #include <image_transport/image_transport.h> 00022 #include <cv_bridge/cv_bridge.h> 00023 00024 // Dynamic reconfigure. 00025 #include <dynamic_reconfigure/server.h> 00026 #include <foscam_8918_driver/foscam_8918_driverConfig.h> 00027 00028 namespace Foscam8918Driver 00029 { 00030 class Foscam8918 00031 { 00032 public: 00035 Foscam8918(ros::NodeHandle nh_); 00036 00038 ~Foscam8918(); 00039 00040 private: 00042 void timerCallback(const ros::TimerEvent& event); 00043 00045 void configCallback(foscam_8918_driver::foscam_8918_driverConfig &config, uint32_t level); 00046 00048 bool connectToCamera(); 00049 00051 dynamic_reconfigure::Server<foscam_8918_driver::foscam_8918_driverConfig> reconfig_srv_; 00053 dynamic_reconfigure::Server<foscam_8918_driver::foscam_8918_driverConfig>::CallbackType reconfig_cb_; 00054 00056 std::string username_; 00057 std::string password_; 00058 std::string ip_address_; 00059 std::string port_; 00060 std::string url_suffix_; 00061 00063 int rate_; 00064 bool have_connection_; 00065 cv::VideoCapture vcap_; 00066 00068 boost::shared_ptr<image_transport::ImageTransport> it_; 00069 image_transport::CameraPublisher image_pub_; 00070 boost::shared_ptr<camera_info_manager::CameraInfoManager> camera_info_manager_; 00071 cv_bridge::CvImage cv_img_; 00072 }; 00073 } 00074 00075 #endif // FOSCAM_DRIVER_H