StereoNode.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <iostream>
4 #include <algorithm>
5 #include <fstream>
6 #include <chrono>
7 #include <opencv2/imgproc/imgproc_c.h>
8 #include <opencv2/core/types.hpp>
9 
10 
11 #include <ros/ros.h>
16 #include <cv_bridge/cv_bridge.h>
18 #include <opencv2/core/core.hpp>
20 
21 #include "System.h"
22 #include "Node.h"
23 
24 class StereoNode : public Node
25 {
26  public:
28  ~StereoNode ();
29  void ImageCallback (const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight);
30 
31 private:
36 
39 };
40 
message_filters::Synchronizer< sync_pol > * sync_
Definition: StereoNode.h:35
Definition: Node.h:54
void ImageCallback(const sensor_msgs::ImageConstPtr &msgLeft, const sensor_msgs::ImageConstPtr &msgRight)
Definition: StereoNode.cc:47
message_filters::Subscriber< sensor_msgs::Image > * right_sub_
Definition: StereoNode.h:34
int resize_vertical
Definition: StereoNode.h:38
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > sync_pol
Definition: StereoNode.h:32
message_filters::Subscriber< sensor_msgs::Image > * left_sub_
Definition: StereoNode.h:33
StereoNode(const ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)
Definition: StereoNode.cc:30
int resize_horizontal
Definition: StereoNode.h:37


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05