19 #ifndef IS_CAMERA_CAMERA_H_
20 #define IS_CAMERA_CAMERA_H_
23 #include <image_transport/image_transport.h>
24 #include <nodelet/nodelet.h>
25 #include <opencv2/imgproc/imgproc.hpp>
26 #include <ff_msgs/SetBool.h>
27 #include <ff_msgs/SetExposure.h>
29 #include <std_msgs/Int32MultiArray.h>
43 static void xioctl(
int fh,
int request,
void *arg);
79 void LoadCameraInfo();
80 void EnableBayer(
bool enable);
82 size_t getNumBayerSubscribers();
83 bool SetExposure(ff_msgs::SetExposure::Request &req, ff_msgs::SetExposure::Response &res);
85 sensor_msgs::CameraInfo info_msg_;
90 size_t img_msg_buffer_idx_;
91 size_t bayer_img_msg_buffer_idx_;
93 std::atomic<bool> thread_running_;
95 ros::Publisher info_pub_;
96 ros::Publisher bayer_pub_;
97 ros::Publisher pub_exposure_;
98 ros::ServiceServer srv_exposure_;
99 std::shared_ptr<V4LStruct> v4l_;
102 ros::Timer config_timer_;
103 ros::Timer auto_exposure_timer_;
104 std::string camera_device_;
105 std::string camera_topic_;
106 std::string bayer_camera_topic_;
107 std::string config_name_;
108 int camera_gain_, camera_exposure_, camera_auto_exposure_;
109 bool calibration_mode_;
118 unsigned int bayer_throttle_ratio_;
119 size_t bayer_throttle_ratio_counter_;
124 double desired_msv_, k_p_, k_i_, max_i_, err_p_, err_i_, tolerance_;
129 #endif // IS_CAMERA_CAMERA_H_