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

#include <Node.h>

Inheritance diagram for Node:
Inheritance graph
[legend]

Public Member Functions

void Init ()
 
 Node (ORB_SLAM2::System::eSensor sensor, ros::NodeHandle &node_handle, image_transport::ImageTransport &image_transport)
 
 ~Node ()
 

Protected Member Functions

void Update ()
 

Protected Attributes

std::string camera_info_topic_
 
ros::Time current_frame_time_
 
ORB_SLAM2::Systemorb_slam_
 

Private Member Functions

void LoadOrbParameters (ORB_SLAM2::ORBParameters &parameters)
 
sensor_msgs::PointCloud2 MapPointsToPointCloud (std::vector< ORB_SLAM2::MapPoint * > map_points)
 
void ParamsChangedCallback (orb_slam2_ros::dynamic_reconfigureConfig &config, uint32_t level)
 
void PublishGBAStatus (bool gba_status)
 
void PublishMapPoints (std::vector< ORB_SLAM2::MapPoint * > map_points)
 
void PublishPositionAsPoseStamped (cv::Mat position)
 
void PublishPositionAsTransform (cv::Mat position)
 
void PublishRenderedImage (cv::Mat image)
 
bool SaveMapSrv (orb_slam2_ros::SaveMap::Request &req, orb_slam2_ros::SaveMap::Response &res)
 
tf2::Transform TransformFromMat (cv::Mat position_mat)
 
tf2::Transform TransformToTarget (tf2::Transform tf_in, std::string frame_in, std::string frame_target)
 

Private Attributes

std::string camera_frame_id_param_
 
dynamic_reconfigure::Server< orb_slam2_ros::dynamic_reconfigureConfig > dynamic_param_server_
 
image_transport::ImageTransport image_transport_
 
bool load_map_param_
 
std::string map_file_name_param_
 
std::string map_frame_id_param_
 
ros::Publisher map_points_publisher_
 
int min_observations_per_point_
 
std::string name_of_node_
 
ros::NodeHandle node_handle_
 
ros::Publisher pose_publisher_
 
bool publish_pointcloud_param_
 
bool publish_pose_param_
 
bool publish_tf_param_
 
image_transport::Publisher rendered_image_publisher_
 
ORB_SLAM2::System::eSensor sensor_
 
ros::ServiceServer service_server_
 
ros::Publisher status_gba_publisher_
 
std::string target_frame_id_param_
 
boost::shared_ptr< tf2_ros::BuffertfBuffer
 
boost::shared_ptr< tf2_ros::TransformListenertfListener
 
std::string voc_file_name_param_
 

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 54 of file Node.h.

Constructor & Destructor Documentation

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

Definition at line 5 of file Node.cc.

Node::~Node ( )

Definition at line 13 of file Node.cc.

Member Function Documentation

void Node::Init ( )

Definition at line 23 of file Node.cc.

void Node::LoadOrbParameters ( ORB_SLAM2::ORBParameters parameters)
private

Definition at line 305 of file Node.cc.

sensor_msgs::PointCloud2 Node::MapPointsToPointCloud ( std::vector< ORB_SLAM2::MapPoint * >  map_points)
private

Definition at line 232 of file Node.cc.

void Node::ParamsChangedCallback ( orb_slam2_ros::dynamic_reconfigureConfig &  config,
uint32_t  level 
)
private

Definition at line 279 of file Node.cc.

void Node::PublishGBAStatus ( bool  gba_status)
private

Definition at line 181 of file Node.cc.

void Node::PublishMapPoints ( std::vector< ORB_SLAM2::MapPoint * >  map_points)
private

Definition at line 90 of file Node.cc.

void Node::PublishPositionAsPoseStamped ( cv::Mat  position)
private

Definition at line 167 of file Node.cc.

void Node::PublishPositionAsTransform ( cv::Mat  position)
private

Definition at line 150 of file Node.cc.

void Node::PublishRenderedImage ( cv::Mat  image)
private

Definition at line 187 of file Node.cc.

bool Node::SaveMapSrv ( orb_slam2_ros::SaveMap::Request &  req,
orb_slam2_ros::SaveMap::Response &  res 
)
private

Definition at line 292 of file Node.cc.

tf2::Transform Node::TransformFromMat ( cv::Mat  position_mat)
private

Definition at line 196 of file Node.cc.

tf2::Transform Node::TransformToTarget ( tf2::Transform  tf_in,
std::string  frame_in,
std::string  frame_target 
)
private

Definition at line 95 of file Node.cc.

void Node::Update ( )
protected

Definition at line 66 of file Node.cc.

Member Data Documentation

std::string Node::camera_frame_id_param_
private

Definition at line 102 of file Node.h.

std::string Node::camera_info_topic_
protected

Definition at line 66 of file Node.h.

ros::Time Node::current_frame_time_
protected

Definition at line 64 of file Node.h.

dynamic_reconfigure::Server<orb_slam2_ros::dynamic_reconfigureConfig> Node::dynamic_param_server_
private

Definition at line 86 of file Node.h.

image_transport::ImageTransport Node::image_transport_
private

Definition at line 97 of file Node.h.

bool Node::load_map_param_
private

Definition at line 106 of file Node.h.

std::string Node::map_file_name_param_
private

Definition at line 104 of file Node.h.

std::string Node::map_frame_id_param_
private

Definition at line 101 of file Node.h.

ros::Publisher Node::map_points_publisher_
private

Definition at line 89 of file Node.h.

int Node::min_observations_per_point_
private

Definition at line 110 of file Node.h.

std::string Node::name_of_node_
private

Definition at line 95 of file Node.h.

ros::NodeHandle Node::node_handle_
private

Definition at line 96 of file Node.h.

ORB_SLAM2::System* Node::orb_slam_
protected

Definition at line 63 of file Node.h.

ros::Publisher Node::pose_publisher_
private

Definition at line 90 of file Node.h.

bool Node::publish_pointcloud_param_
private

Definition at line 107 of file Node.h.

bool Node::publish_pose_param_
private

Definition at line 109 of file Node.h.

bool Node::publish_tf_param_
private

Definition at line 108 of file Node.h.

image_transport::Publisher Node::rendered_image_publisher_
private

Definition at line 88 of file Node.h.

ORB_SLAM2::System::eSensor Node::sensor_
private

Definition at line 99 of file Node.h.

ros::ServiceServer Node::service_server_
private

Definition at line 93 of file Node.h.

ros::Publisher Node::status_gba_publisher_
private

Definition at line 91 of file Node.h.

std::string Node::target_frame_id_param_
private

Definition at line 103 of file Node.h.

boost::shared_ptr<tf2_ros::Buffer> Node::tfBuffer
private

Definition at line 79 of file Node.h.

boost::shared_ptr<tf2_ros::TransformListener> Node::tfListener
private

Definition at line 80 of file Node.h.

std::string Node::voc_file_name_param_
private

Definition at line 105 of file Node.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