#include <pluginlib/class_list_macros.h>
#include <nodelet/nodelet.h>
#include <image_transport/image_transport.h>
#include <ros/ros.h>
#include <ros/package.h>
#include <std_srvs/SetBool.h>
#include <librealsense2/rs.hpp>
#include <librealsense2/rsutil.h>
#include <librealsense2/hpp/rs_processing.hpp>
#include <librealsense2/rs_advanced_mode.hpp>
#include <cv_bridge/cv_bridge.h>
#include <constants.h>
#include <realsense2_camera/Extrinsics.h>
#include <realsense2_camera/IMUInfo.h>
#include <csignal>
#include <eigen3/Eigen/Geometry>
#include <fstream>
#include <thread>
#include <std_srvs/Empty.h>
Go to the source code of this file.
|
const stream_index_pair | realsense2_camera::ACCEL {RS2_STREAM_ACCEL, 0} |
|
const stream_index_pair | realsense2_camera::COLOR {RS2_STREAM_COLOR, 0} |
|
const stream_index_pair | realsense2_camera::CONFIDENCE {RS2_STREAM_CONFIDENCE, 0} |
|
const stream_index_pair | realsense2_camera::DEPTH {RS2_STREAM_DEPTH, 0} |
|
const stream_index_pair | realsense2_camera::FISHEYE {RS2_STREAM_FISHEYE, 0} |
|
const stream_index_pair | realsense2_camera::FISHEYE1 {RS2_STREAM_FISHEYE, 1} |
|
const stream_index_pair | realsense2_camera::FISHEYE2 {RS2_STREAM_FISHEYE, 2} |
|
const stream_index_pair | realsense2_camera::GYRO {RS2_STREAM_GYRO, 0} |
|
const std::vector< stream_index_pair > | realsense2_camera::HID_STREAMS = {GYRO, ACCEL, POSE} |
|
const std::vector< stream_index_pair > | realsense2_camera::IMAGE_STREAMS |
|
const stream_index_pair | realsense2_camera::INFRA0 {RS2_STREAM_INFRARED, 0} |
|
const stream_index_pair | realsense2_camera::INFRA1 {RS2_STREAM_INFRARED, 1} |
|
const stream_index_pair | realsense2_camera::INFRA2 {RS2_STREAM_INFRARED, 2} |
|
const stream_index_pair | realsense2_camera::POSE {RS2_STREAM_POSE, 0} |
|