Go to the documentation of this file.
34 #ifndef MULTISENSE_ROS_CAMERA_H
35 #define MULTISENSE_ROS_CAMERA_H
49 #include <stereo_msgs/DisparityImage.h>
50 #include <sensor_msgs/PointCloud2.h>
53 #include <multisense_lib/MultiSenseChannel.hh>
54 #include <multisense_ros/RawCamData.h>
63 const std::string& tf_prefix);
94 static constexpr
char LEFT[] =
"left";
95 static constexpr
char RIGHT[] =
"right";
96 static constexpr
char AUX[] =
"aux";
341 std::unordered_map<crl::multisense::DataSource, std::shared_ptr<BufferWrapper<crl::multisense::image::Header>>>
image_buffers_;
diagnostic_updater::Updater diagnostic_updater_
sensor_msgs::Image left_rect_image_
image_transport::ImageTransport disparity_right_transport_
sensor_msgs::Image left_rgb_image_
void borderClipChanged(const BorderClip &borderClipType, double borderClipValue)
sensor_msgs::Image left_disparity_cost_image_
static constexpr char DISPARITY_TOPIC[]
image_transport::ImageTransport left_rgb_transport_
crl::multisense::Channel * driver_
image_transport::CameraPublisher right_rect_cam_pub_
static constexpr char RECT_CAMERA_INFO_TOPIC[]
const std::string frame_id_aux_
ros::Publisher raw_cam_cal_pub_
const std::string frame_id_rectified_aux_
std::map< crl::multisense::DataSource, int32_t > StreamMapType
BorderClip border_clip_type_
static constexpr char AUX_RECTIFIED_FRAME[]
static constexpr char LEFT_RECTIFIED_FRAME[]
image_transport::Publisher left_disparity_pub_
image_transport::ImageTransport left_rect_transport_
std::vector< uint8_t > pointcloud_color_buffer_
image_transport::Publisher ni_depth_cam_pub_
void publishAllCameraInfo()
void colorImageCallback(const crl::multisense::image::Header &header)
static constexpr char LEFT[]
ros::Publisher depth_cam_info_pub_
sensor_msgs::Image right_disparity_image_
ros::Publisher right_stereo_disparity_pub_
image_transport::CameraPublisher left_rect_cam_pub_
ros::Timer diagnostic_trigger_
image_transport::Publisher aux_rgb_cam_pub_
static constexpr char GROUND_SURFACE[]
std::vector< crl::multisense::system::DeviceMode > device_modes_
image_transport::CameraPublisher aux_rgb_rect_cam_pub_
sensor_msgs::Image aux_rgb_image_
sensor_msgs::Image aux_rgb_rect_image_
static constexpr char COST_TOPIC[]
multisense_ros::RawCamData raw_cam_data_
void groundSurfaceSplineCallback(const crl::multisense::ground_surface::Header &header)
Camera(crl::multisense::Channel *driver, const std::string &tf_prefix)
static constexpr char LEFT_CAMERA_FRAME[]
bool can_support_ground_surface_
void rawCamDataCallback(const crl::multisense::image::Header &header)
image_transport::ImageTransport right_mono_transport_
ros::NodeHandle right_nh_
void deviceStatusDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
image_transport::Publisher right_disparity_pub_
image_transport::Publisher aux_mono_cam_pub_
const std::string frame_id_origin_
sensor_msgs::Image aux_rect_image_
image_transport::ImageTransport left_rgb_rect_transport_
crl::multisense::system::VersionInfo version_info_
ros::Publisher luma_organized_point_cloud_pub_
void colorizeCallback(const crl::multisense::image::Header &header)
static constexpr char RAW_CAM_CAL_TOPIC[]
sensor_msgs::Image right_rect_image_
ros::Publisher aux_mono_cam_info_pub_
image_transport::ImageTransport ground_surface_transport_
image_transport::ImageTransport aux_rgb_transport_
double border_clip_value_
ros::Publisher left_mono_cam_info_pub_
image_transport::ImageTransport aux_mono_transport_
image_transport::ImageTransport right_rect_transport_
ros::Publisher ground_surface_info_pub_
image_transport::ImageTransport disparity_left_transport_
sensor_msgs::Image aux_mono_image_
static constexpr char RECT_COLOR_CAMERA_INFO_TOPIC[]
static constexpr char RIGHT[]
static constexpr char RAW_CAM_CONFIG_TOPIC[]
const std::string frame_id_rectified_left_
ros::Publisher histogram_pub_
image_transport::CameraPublisher left_rgb_rect_cam_pub_
void pointCloudCallback(const crl::multisense::image::Header &header)
ros::Publisher ground_surface_spline_pub_
ros::Publisher left_stereo_disparity_pub_
static constexpr char POINTCLOUD_TOPIC[]
static constexpr char DEPTH_TOPIC[]
sensor_msgs::Image left_rgb_rect_image_
ros::Publisher left_rect_cam_info_pub_
static constexpr char GROUND_SURFACE_POINT_SPLINE_TOPIC[]
void disconnectStream(crl::multisense::DataSource disableMask)
void deviceInfoDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
const std::string frame_id_rectified_right_
void extrinsicsChanged(crl::multisense::system::ExternalCalibration extrinsics)
ros::Publisher device_info_pub_
static constexpr char AUX_CAMERA_FRAME[]
ros::Publisher aux_rgb_rect_cam_info_pub_
ros::Publisher aux_rect_cam_info_pub_
double pointcloud_max_range_
static constexpr char COLOR_TOPIC[]
ros::Publisher color_organized_point_cloud_pub_
image_transport::ImageTransport left_mono_transport_
static constexpr char HEAD_FRAME[]
image_transport::Publisher left_rgb_cam_pub_
sensor_msgs::Image ground_surface_image_
static constexpr char COLOR_POINTCLOUD_TOPIC[]
static constexpr char ORGANIZED_POINTCLOUD_TOPIC[]
ros::Publisher right_rect_cam_info_pub_
ros::NodeHandle ground_surface_nh_
static constexpr char CALIBRATION[]
ros::Publisher left_rgb_rect_cam_info_pub_
std::shared_ptr< StereoCalibrationManager > stereo_calibration_manager_
image_transport::Publisher depth_cam_pub_
ros::Publisher luma_point_cloud_pub_
image_transport::ImageTransport aux_rect_transport_
stereo_msgs::DisparityImage right_stereo_disparity_
static constexpr char HISTOGRAM_TOPIC[]
void updateConfig(const crl::multisense::image::Config &config)
sensor_msgs::PointCloud2 color_point_cloud_
static constexpr char COST_CAMERA_INFO_TOPIC[]
Struct containing parameters for drawing a pointcloud representation of a B-Spline model.
void groundSurfaceSplineDrawParametersChanged(const ground_surface_utilities::SplineDrawParameters &spline_draw_params)
void histogramCallback(const crl::multisense::image::Header &header)
static constexpr char RECT_COLOR_TOPIC[]
ros::Publisher left_rgb_cam_info_pub_
static constexpr char RAW_CAM_DATA_TOPIC[]
sensor_msgs::Image depth_image_
sensor_msgs::PointCloud2 color_organized_point_cloud_
ros::Publisher aux_rgb_cam_info_pub_
void disparityImageCallback(const crl::multisense::image::Header &header)
image_transport::ImageTransport disparity_cost_transport_
static constexpr char AUX[]
void rectCallback(const crl::multisense::image::Header &header)
void connectStream(crl::multisense::DataSource enableMask)
image_transport::Publisher left_mono_cam_pub_
sensor_msgs::PointCloud2 luma_point_cloud_
static constexpr char COLOR_ORGANIZED_POINTCLOUD_TOPIC[]
image_transport::Publisher ground_surface_cam_pub_
image_transport::CameraPublisher aux_rect_cam_pub_
ros::Publisher left_cost_cam_info_pub_
void jpegImageCallback(const crl::multisense::image::Header &header)
static constexpr char RECT_TOPIC[]
image_transport::ImageTransport depth_transport_
void monoCallback(const crl::multisense::image::Header &header)
stereo_msgs::DisparityImage left_stereo_disparity_
const std::string frame_id_head_
sensor_msgs::PointCloud2 luma_organized_point_cloud_
static constexpr char GROUND_SURFACE_INFO_TOPIC[]
std::unordered_map< crl::multisense::DataSource, std::shared_ptr< BufferWrapper< crl::multisense::image::Header > > > image_buffers_
ground_surface_utilities::SplineDrawParameters spline_draw_params_
static constexpr char OPENNI_DEPTH_TOPIC[]
static constexpr char MONO_TOPIC[]
ros::Publisher raw_cam_config_pub_
StreamMapType stream_map_
void maxPointCloudRangeChanged(double range)
ros::Publisher left_disp_cam_info_pub_
void depthCallback(const crl::multisense::image::Header &header)
void diagnosticTimerCallback(const ros::TimerEvent &)
static constexpr char RIGHT_CAMERA_FRAME[]
sensor_msgs::Image left_mono_image_
static constexpr char DISPARITY_CAMERA_INFO_TOPIC[]
ros::NodeHandle calibration_nh_
static constexpr char ORIGIN_FRAME[]
const std::string frame_id_left_
static constexpr char COLOR_CAMERA_INFO_TOPIC[]
static constexpr char DEVICE_INFO_TOPIC[]
void groundSurfaceCallback(const crl::multisense::image::Header &header)
image_transport::ImageTransport aux_rgb_rect_transport_
static constexpr char GROUND_SURFACE_IMAGE_TOPIC[]
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
crl::multisense::system::DeviceInfo device_info_
ros::Publisher right_mono_cam_info_pub_
image_transport::Publisher right_mono_cam_pub_
sensor_msgs::Image right_mono_image_
ros::NodeHandle device_nh_
sensor_msgs::Image ni_depth_image_
image_transport::ImageTransport ni_depth_transport_
ros::Publisher color_point_cloud_pub_
static constexpr char MONO_CAMERA_INFO_TOPIC[]
const std::string frame_id_right_
static constexpr char RIGHT_RECTIFIED_FRAME[]
static constexpr char DISPARITY_IMAGE_TOPIC[]
ros::Publisher raw_cam_data_pub_
static constexpr char DEPTH_CAMERA_INFO_TOPIC[]
std::vector< uint8_t > pointcloud_rect_color_buffer_
ros::Publisher right_disp_cam_info_pub_
sensor_msgs::Image left_disparity_image_
image_transport::Publisher left_disparity_cost_pub_