Public Member Functions | Private Types | Private Attributes | List of all members
RGBDNode Class Reference

#include <RGBDNode.h>

Inheritance diagram for RGBDNode:
Inheritance graph
[legend]

Public Member Functions

void ImageCallback (const sensor_msgs::ImageConstPtr &msgRGB, const sensor_msgs::ImageConstPtr &msgD)
 
 RGBDNode (const ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)
 
 ~RGBDNode ()
 
- Public Member Functions inherited from Node
void Init ()
 
 Node (ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)
 
 ~Node ()
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image > sync_pol
 

Private Attributes

message_filters::Subscriber< sensor_msgs::Image > * depth_subscriber_
 
message_filters::Subscriber< sensor_msgs::Image > * rgb_subscriber_
 
message_filters::Synchronizer< sync_pol > * sync_
 

Additional Inherited Members

- Protected Member Functions inherited from Node
void Update ()
 
- Protected Attributes inherited from Node
std::string camera_info_topic_
 
ros::Time current_frame_time_
 
ORB_SLAM2::Systemorb_slam_
 

Detailed Description

This file is part of ORB-SLAM2.

Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at="" unizar="" dot="" es>=""> (University of Zaragoza) For more information see https://github.com/raulmur/ORB_SLAM2

ORB-SLAM2 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.

ORB-SLAM2 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 ORB-SLAM2. If not, see http://www.gnu.org/licenses/.

Definition at line 43 of file RGBDNode.h.

Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> RGBDNode::sync_pol
private

Definition at line 51 of file RGBDNode.h.

Constructor & Destructor Documentation

RGBDNode::RGBDNode ( const ORB_SLAM2::System::eSensor  sensor,
ros::NodeHandle node_handle,
image_transport::ImageTransport image_transport 
)

Definition at line 29 of file RGBDNode.cc.

RGBDNode::~RGBDNode ( )

Definition at line 39 of file RGBDNode.cc.

Member Function Documentation

void RGBDNode::ImageCallback ( const sensor_msgs::ImageConstPtr &  msgRGB,
const sensor_msgs::ImageConstPtr &  msgD 
)

Definition at line 46 of file RGBDNode.cc.

Member Data Documentation

message_filters::Subscriber<sensor_msgs::Image>* RGBDNode::depth_subscriber_
private

Definition at line 53 of file RGBDNode.h.

message_filters::Subscriber<sensor_msgs::Image>* RGBDNode::rgb_subscriber_
private

Definition at line 52 of file RGBDNode.h.

message_filters::Synchronizer<sync_pol>* RGBDNode::sync_
private

Definition at line 54 of file RGBDNode.h.


The documentation for this class was generated from the following files:


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