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
00034
00035 #ifndef _STEREO_NODE_H_
00036 #define _STEREO_NODE_H_
00037
00038 #include "CameraNode.h"
00039
00040
00041 #include <ros/ros.h>
00042 #include <ros/package.h>
00043 #include <sensor_msgs/Image.h>
00044 #include <sensor_msgs/CameraInfo.h>
00045 #include <sensor_msgs/SetCameraInfo.h>
00046 #include <cv_bridge/cv_bridge.h>
00047 #include <image_transport/image_transport.h>
00048 #include <camera_calibration_parsers/parse_ini.h>
00049
00050
00051 #include <dynamic_reconfigure/server.h>
00052 #include "ueye/stereoConfig.h"
00053
00054
00055 #include <sstream>
00056 #include <fstream>
00057
00058
00059 #include <ueye/Camera.h>
00060
00061 namespace ueye
00062 {
00063
00064 class StereoNode
00065 {
00066 public:
00067 StereoNode(ros::NodeHandle node, ros::NodeHandle private_nh);
00068 ~StereoNode();
00069
00070 private:
00071
00072 void reconfig(stereoConfig &config, uint32_t level);
00073 void reconfigCam(stereoConfig &config, uint32_t level, Camera &cam);
00074 void timerCallback(const ros::TimerEvent& event);
00075 void timerForceTrigger(const ros::TimerEvent& event);
00076 bool setCameraInfoL(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
00077 bool setCameraInfoR(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp);
00078 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp, Camera& cam,
00079 sensor_msgs::CameraInfo &msg_info);
00080
00081 void loadIntrinsics(Camera &cam, sensor_msgs::CameraInfo &msg_info);
00082 sensor_msgs::ImagePtr processFrame(IplImage* frame, Camera &cam, cv_bridge::CvImage &converter,
00083 sensor_msgs::CameraInfoPtr &info, sensor_msgs::CameraInfo &msg_info);
00084 void publishImageL(IplImage * frame);
00085 void publishImageR(IplImage * frame);
00086 void startCamera();
00087 void stopCamera();
00088 void closeCamera();
00089 void handlePath(std::string &path);
00090
00091 dynamic_reconfigure::Server<stereoConfig> srv_;
00092 ros::Timer timer_;
00093 ros::Timer timer_force_trigger_;
00094 sensor_msgs::CameraInfo l_msg_camera_info_, r_msg_camera_info_;
00095
00096 cv_bridge::CvImage l_converter_, r_converter_;
00097 ueye::Camera l_cam_, r_cam_;
00098 bool running_;
00099 bool configured_;
00100 bool force_streaming_;
00101 std::string config_path_;
00102 int trigger_mode_;
00103 bool auto_exposure_;
00104 bool auto_gain_;
00105 int zoom_;
00106 ros::Time l_stamp_, r_stamp_;
00107
00108
00109 image_transport::ImageTransport it_;
00110 image_transport::CameraPublisher l_pub_stream_, r_pub_stream_;
00111 ros::ServiceServer l_srv_cam_info_, r_srv_cam_info_;
00112 };
00113
00114 }
00115
00116 #endif // _STEREO_NODE_H_