Classes | Namespaces | Enumerations | Variables
tango_ros_nodelet.h File Reference
#include <atomic>
#include <chrono>
#include <condition_variable>
#include <mutex>
#include <string>
#include <thread>
#include <time.h>
#include <tango_3d_reconstruction/tango_3d_reconstruction_api.h>
#include <tango_client_api/tango_client_api.h>
#include <tango_support/tango_support.h>
#include <opencv2/core/core.hpp>
#include <camera_info_manager/camera_info_manager.h>
#include <cv_bridge/cv_bridge.h>
#include <geometry_msgs/TransformStamped.h>
#include <image_geometry/pinhole_camera_model.h>
#include <image_transport/image_transport.h>
#include <nav_msgs/OccupancyGrid.h>
#include <nodelet/nodelet.h>
#include <ros/ros.h>
#include <ros/node_handle.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/LaserScan.h>
#include <sensor_msgs/PointCloud2.h>
#include <tango_ros_messages/GetMapName.h>
#include <tango_ros_messages/GetMapUuids.h>
#include <tango_ros_messages/LoadOccupancyGrid.h>
#include <tango_ros_messages/SaveMap.h>
#include <tango_ros_messages/TangoConnect.h>
#include <tf/transform_broadcaster.h>
#include <tf2_ros/static_transform_broadcaster.h>
#include <visualization_msgs/MarkerArray.h>
#include "tango_ros_native/PublisherConfig.h"
Include dependency graph for tango_ros_nodelet.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  tango_ros_native::PublishThread
 
class  tango_ros_native::TangoRosNodelet
 

Namespaces

 tango_ros_native
 

Enumerations

enum  tango_ros_native::LocalizationMode { tango_ros_native::ODOMETRY = 1, tango_ros_native::ONLINE_SLAM = 2, tango_ros_native::LOCALIZATION = 3 }
 
enum  tango_ros_native::TangoStatus { tango_ros_native::TangoStatus::UNKNOWN = 0, tango_ros_native::TangoStatus::SERVICE_NOT_CONNECTED, tango_ros_native::TangoStatus::NO_FIRST_VALID_POSE, tango_ros_native::TangoStatus::SERVICE_CONNECTED }
 

Variables

const std::string tango_ros_native::AREA_DESCRIPTION_FRAME_ID_PARAM_NAME = "area_description_frame_id"
 
const std::string tango_ros_native::AREA_DESCRIPTION_T_START_OF_SERVICE_TOPIC_NAME = "transform/area_description_T_start_of_service"
 
const std::string tango_ros_native::COLOR_IMAGE_TOPIC_NAME = "camera/color_1/image_raw"
 
const std::string tango_ros_native::COLOR_MESH_TOPIC_NAME = "reconstruction/mesh"
 
const std::string tango_ros_native::COLOR_RECTIFIED_IMAGE_TOPIC_NAME = "camera/color_1/image_rect"
 
const std::string tango_ros_native::CONNECT_SERVICE_NAME = "connect"
 
const std::string tango_ros_native::CREATE_NEW_MAP_PARAM_NAME = "create_new_map"
 
const std::string tango_ros_native::DATASET_DEFAULT_DIRECTORY = "/sdcard/tango_ros_streamer/datasets/"
 
const std::string tango_ros_native::DATASET_DIRECTORY_PARAM_NAME = "dataset_directory"
 
const std::string tango_ros_native::DATASET_UUID_PARAM_NAME = "dataset_uuid"
 
const std::string tango_ros_native::ENABLE_3DR_MESH_PARAM_NAME = "enable_3dr_mesh"
 
const std::string tango_ros_native::ENABLE_3DR_OCCUPANCY_GRID_PARAM_NAME = "enable_3dr_occupancy_grid"
 
const std::string tango_ros_native::ENABLE_COLOR_CAMERA_PARAM_NAME = "enable_color_camera"
 
const std::string tango_ros_native::ENABLE_DEPTH_PARAM_NAME = "enable_depth"
 
const std::string tango_ros_native::FISHEYE_IMAGE_TOPIC_NAME = "camera/fisheye_1/image_raw"
 
const std::string tango_ros_native::FISHEYE_RECTIFIED_IMAGE_TOPIC_NAME = "camera/fisheye_1/image_rect"
 
const std::string tango_ros_native::GET_MAP_NAME_SERVICE_NAME = "get_map_name"
 
const std::string tango_ros_native::GET_MAP_UUIDS_SERVICE_NAME = "get_map_uuids"
 
const float tango_ros_native::LASER_SCAN_ANGLE_INCREMENT = 3.1415 / 360
 
const float tango_ros_native::LASER_SCAN_ANGLE_MAX = 3.1415
 
const float tango_ros_native::LASER_SCAN_ANGLE_MIN = 0.
 
const std::string tango_ros_native::LASER_SCAN_FRAME_ID = "laser"
 
const float tango_ros_native::LASER_SCAN_SCAN_TIME = 0.3333
 
const float tango_ros_native::LASER_SCAN_TIME_INCREMENT = 0.0
 
const std::string tango_ros_native::LASER_SCAN_TOPIC_NAME = "laser_scan"
 
const std::string tango_ros_native::LOAD_OCCUPANCY_GRID_SERVICE_NAME = "load_occupancy_grid"
 
const std::string tango_ros_native::LOCALIZATION_MAP_UUID_PARAM_NAME = "localization_map_uuid"
 
const std::string tango_ros_native::LOCALIZATION_MODE_PARAM_NAME = "localization_mode"
 
const int tango_ros_native::NUMBER_OF_STATIC_TRANSFORMS = 5
 
const std::string tango_ros_native::OCCUPANCY_GRID_DEFAULT_DIRECTORY = "/sdcard/tango_ros_streamer/occupancy_grids/"
 
const std::string tango_ros_native::OCCUPANCY_GRID_DIRECTORY_PARAM_NAME = "occupancy_grid_directory"
 
const std::string tango_ros_native::OCCUPANCY_GRID_TOPIC_NAME = "reconstruction/occupancy_grid"
 
const std::string tango_ros_native::POINT_CLOUD_TOPIC_NAME = "point_cloud"
 
const std::string tango_ros_native::PUBLISH_POSE_ON_TF_PARAM_NAME = "publish_pose_on_tf"
 
const std::string tango_ros_native::SAVE_MAP_SERVICE_NAME = "save_map"
 
const std::string tango_ros_native::START_OF_SERVICE_FRAME_ID_PARAM_NAME = "start_of_service_frame_id"
 
const std::string tango_ros_native::START_OF_SERVICE_T_DEVICE_TOPIC_NAME = "transform/start_of_service_T_device"
 
const std::string tango_ros_native::STATIC_OCCUPANCY_GRID_TOPIC_NAME = "static_occupancy_grid"
 
const std::string tango_ros_native::TANGO_STATUS_TOPIC_NAME = "status"
 
const std::string tango_ros_native::USE_TF_STATIC_PARAM_NAME = "use_tf_static"
 


tango_ros_native
Author(s):
autogenerated on Mon Jun 10 2019 15:37:51