-
Notifications
You must be signed in to change notification settings - Fork 11
/
Copy pathsync_images.h
65 lines (54 loc) · 2.35 KB
/
sync_images.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
/**
* The celex5_calibration ROS package,
* used to calibrate camera parameters for CeleX5-MIPI Event-based Camera.
*
* Copyright (C) 2020 Kehan.Xue<kehan.xue@gmail.com>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef CELEX5_CALIBRATION_SRC_EXTRINSICS_SYNCIMAGES_H_
#define CELEX5_CALIBRATION_SRC_EXTRINSICS_SYNCIMAGES_H_
#include <string>
#include <boost/thread/thread.hpp>
#include <boost/filesystem.hpp>
#include <ros/ros.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <sensor_msgs/Image.h>
#include <cv_bridge/cv_bridge.h>
#include <ddynamic_reconfigure/ddynamic_reconfigure.h>
#include <opencv2/opencv.hpp>
class SyncImages {
public:
explicit SyncImages(const ros::NodeHandle &nh = ros::NodeHandle("~"));
virtual ~SyncImages();
private:
void SyncImagesCallback(const sensor_msgs::ImageConstPtr &frame_msg,
const sensor_msgs::ImageConstPtr &events_msg);
// void FrameImageCallback(const sensor_msgs::ImageConstPtr &frame_msg);
// void EventsImageCallback(const sensor_msgs::ImageConstPtr &events_msg);
ros::NodeHandle nh_;
typedef message_filters::Subscriber<sensor_msgs::Image> MfImageSub;
std::shared_ptr<MfImageSub> p_frame_sync_sub_;
std::shared_ptr<MfImageSub> p_events_sync_sub_;
std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> p_ddyn_rec_;
bool save_;
// ros::Subscriber frame_sub_;
// ros::Subscriber events_sub_;
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> SyncPolicy;
std::shared_ptr<message_filters::Synchronizer<SyncPolicy>> p_sync_;
std::string store_dir_;
};
#endif //CELEX5_CALIBRATION_SRC_EXTRINSICS_SYNCIMAGES_H_