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

#include <MonoNode.h>

Inheritance diagram for MonoNode:
Inheritance graph
[legend]

Public Member Functions

void ImageCallback (const sensor_msgs::ImageConstPtr &msg)
 
 MonoNode (const ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)
 
 ~MonoNode ()
 
- 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 Attributes

image_transport::Subscriber image_subscriber
 

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 40 of file MonoNode.h.

Constructor & Destructor Documentation

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

Definition at line 28 of file MonoNode.cc.

MonoNode::~MonoNode ( )

Definition at line 34 of file MonoNode.cc.

Member Function Documentation

void MonoNode::ImageCallback ( const sensor_msgs::ImageConstPtr &  msg)

Definition at line 38 of file MonoNode.cc.

Member Data Documentation

image_transport::Subscriber MonoNode::image_subscriber
private

Definition at line 48 of file MonoNode.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