Main Page
Modules
Namespaces
Classes
Files
File List
File Members
ros
include
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
>
12
#include <
message_filters/subscriber.h
>
13
#include <
message_filters/time_synchronizer.h
>
14
#include <
message_filters/sync_policies/approximate_time.h
>
15
#include <
image_transport/image_transport.h
>
16
#include <
cv_bridge/cv_bridge.h
>
17
#include <
sensor_msgs/image_encodings.h
>
18
#include <opencv2/core/core.hpp>
19
#include <
tf/transform_broadcaster.h
>
20
21
#include "
System.h
"
22
#include "
Node.h
"
23
24
class
StereoNode
:
public
Node
25
{
26
public
:
27
StereoNode
(
const
ORB_SLAM2::System::eSensor
sensor,
ros::NodeHandle
&node_handle,
image_transport::ImageTransport
&
image_transport
);
28
~StereoNode
();
29
void
ImageCallback
(
const
sensor_msgs::ImageConstPtr& msgLeft,
const
sensor_msgs::ImageConstPtr& msgRight);
30
31
private
:
32
typedef
message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image>
sync_pol
;
33
message_filters::Subscriber<sensor_msgs::Image>
*
left_sub_
;
34
message_filters::Subscriber<sensor_msgs::Image>
*
right_sub_
;
35
message_filters::Synchronizer<sync_pol>
*
sync_
;
36
37
int
resize_horizontal
;
38
int
resize_vertical
;
39
};
40
StereoNode
Definition:
StereoNode.h:24
message_filters::Synchronizer
ros::NodeHandle
StereoNode::sync_
message_filters::Synchronizer< sync_pol > * sync_
Definition:
StereoNode.h:35
Node
Definition:
Node.h:54
StereoNode::ImageCallback
void ImageCallback(const sensor_msgs::ImageConstPtr &msgLeft, const sensor_msgs::ImageConstPtr &msgRight)
Definition:
StereoNode.cc:47
StereoNode::right_sub_
message_filters::Subscriber< sensor_msgs::Image > * right_sub_
Definition:
StereoNode.h:34
subscriber.h
Node.h
image_transport.h
StereoNode::~StereoNode
~StereoNode()
Definition:
StereoNode.cc:40
image_transport
transform_broadcaster.h
time_synchronizer.h
cv_bridge.h
System.h
approximate_time.h
ORB_SLAM2::System::eSensor
eSensor
Definition:
System.h:54
StereoNode::resize_vertical
int resize_vertical
Definition:
StereoNode.h:38
ros.h
StereoNode::sync_pol
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > sync_pol
Definition:
StereoNode.h:32
message_filters::sync_policies::ApproximateTime
StereoNode::left_sub_
message_filters::Subscriber< sensor_msgs::Image > * left_sub_
Definition:
StereoNode.h:33
image_transport::ImageTransport
image_encodings.h
message_filters::Subscriber< sensor_msgs::Image >
StereoNode::StereoNode
StereoNode(const ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)
Definition:
StereoNode.cc:30
StereoNode::resize_horizontal
int resize_horizontal
Definition:
StereoNode.h:37
orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05