Public Member Functions | Private Types | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
multisense_ros::Camera Class Reference

#include <camera.h>

Public Member Functions

void borderClipChanged (const BorderClip &borderClipType, double borderClipValue)
 
 Camera (crl::multisense::Channel *driver, const std::string &tf_prefix)
 
void colorImageCallback (const crl::multisense::image::Header &header)
 
void colorizeCallback (const crl::multisense::image::Header &header)
 
void depthCallback (const crl::multisense::image::Header &header)
 
void disparityImageCallback (const crl::multisense::image::Header &header)
 
void extrinsicsChanged (crl::multisense::system::ExternalCalibration extrinsics)
 
void groundSurfaceCallback (const crl::multisense::image::Header &header)
 
void groundSurfaceSplineCallback (const crl::multisense::ground_surface::Header &header)
 
void groundSurfaceSplineDrawParametersChanged (const ground_surface_utilities::SplineDrawParameters &spline_draw_params)
 
void histogramCallback (const crl::multisense::image::Header &header)
 
void jpegImageCallback (const crl::multisense::image::Header &header)
 
void maxPointCloudRangeChanged (double range)
 
void monoCallback (const crl::multisense::image::Header &header)
 
void pointCloudCallback (const crl::multisense::image::Header &header)
 
void rawCamDataCallback (const crl::multisense::image::Header &header)
 
void rectCallback (const crl::multisense::image::Header &header)
 
void timeSyncChanged (bool ptp_enabled, int32_t ptp_time_offset_sec)
 
void updateConfig (const crl::multisense::image::Config &config)
 
 ~Camera ()
 

Private Types

typedef std::map< crl::multisense::DataSource, int32_t > StreamMapType
 

Private Member Functions

void connectStream (crl::multisense::DataSource enableMask)
 
ros::Time convertImageTimestamp (uint32_t time_secs, uint32_t time_microsecs)
 
void deviceInfoDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void deviceStatusDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void diagnosticTimerCallback (const ros::TimerEvent &)
 
void disconnectStream (crl::multisense::DataSource disableMask)
 
void ptpStatusDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void publishAllCameraInfo ()
 
void stop ()
 

Private Attributes

ros::Publisher aux_mono_cam_info_pub_
 
image_transport::Publisher aux_mono_cam_pub_
 
sensor_msgs::Image aux_mono_image_
 
image_transport::ImageTransport aux_mono_transport_
 
ros::NodeHandle aux_nh_
 
ros::Publisher aux_rect_cam_info_pub_
 
image_transport::CameraPublisher aux_rect_cam_pub_
 
sensor_msgs::Image aux_rect_image_
 
image_transport::ImageTransport aux_rect_transport_
 
ros::Publisher aux_rgb_cam_info_pub_
 
image_transport::Publisher aux_rgb_cam_pub_
 
sensor_msgs::Image aux_rgb_image_
 
ros::Publisher aux_rgb_rect_cam_info_pub_
 
image_transport::CameraPublisher aux_rgb_rect_cam_pub_
 
sensor_msgs::Image aux_rgb_rect_image_
 
image_transport::ImageTransport aux_rgb_rect_transport_
 
image_transport::ImageTransport aux_rgb_transport_
 
BorderClip border_clip_type_ = BorderClip::NONE
 
double border_clip_value_ = 0.0
 
ros::NodeHandle calibration_nh_
 
bool can_support_ground_surface_ = false
 
sensor_msgs::PointCloud2 color_organized_point_cloud_
 
ros::Publisher color_organized_point_cloud_pub_
 
sensor_msgs::PointCloud2 color_point_cloud_
 
ros::Publisher color_point_cloud_pub_
 
ros::Publisher depth_cam_info_pub_
 
image_transport::Publisher depth_cam_pub_
 
sensor_msgs::Image depth_image_
 
image_transport::ImageTransport depth_transport_
 
crl::multisense::system::DeviceInfo device_info_
 
ros::Publisher device_info_pub_
 
std::vector< crl::multisense::system::DeviceModedevice_modes_
 
ros::NodeHandle device_nh_
 
ros::Timer diagnostic_trigger_
 
diagnostic_updater::Updater diagnostic_updater_
 
image_transport::ImageTransport disparity_cost_transport_
 
image_transport::ImageTransport disparity_left_transport_
 
image_transport::ImageTransport disparity_right_transport_
 
crl::multisense::Channeldriver_ = nullptr
 
const std::string frame_id_aux_
 
const std::string frame_id_head_
 
const std::string frame_id_left_
 
const std::string frame_id_origin_
 
const std::string frame_id_rectified_aux_
 
const std::string frame_id_rectified_left_
 
const std::string frame_id_rectified_right_
 
const std::string frame_id_right_
 
image_transport::Publisher ground_surface_cam_pub_
 
sensor_msgs::Image ground_surface_image_
 
ros::Publisher ground_surface_info_pub_
 
ros::NodeHandle ground_surface_nh_
 
ros::Publisher ground_surface_spline_pub_
 
image_transport::ImageTransport ground_surface_transport_
 
bool has_aux_camera_ = false
 
bool has_color_ = false
 
bool has_left_camera_ = false
 
bool has_right_camera_ = false
 
ros::Publisher histogram_pub_
 
std::unordered_map< crl::multisense::DataSource, std::shared_ptr< BufferWrapper< crl::multisense::image::Header > > > image_buffers_
 
int64_t last_frame_id_ = -1
 
ros::Publisher left_cost_cam_info_pub_
 
ros::Publisher left_disp_cam_info_pub_
 
sensor_msgs::Image left_disparity_cost_image_
 
image_transport::Publisher left_disparity_cost_pub_
 
sensor_msgs::Image left_disparity_image_
 
image_transport::Publisher left_disparity_pub_
 
ros::Publisher left_mono_cam_info_pub_
 
image_transport::Publisher left_mono_cam_pub_
 
sensor_msgs::Image left_mono_image_
 
image_transport::ImageTransport left_mono_transport_
 
ros::NodeHandle left_nh_
 
ros::Publisher left_rect_cam_info_pub_
 
image_transport::CameraPublisher left_rect_cam_pub_
 
sensor_msgs::Image left_rect_image_
 
image_transport::ImageTransport left_rect_transport_
 
ros::Publisher left_rgb_cam_info_pub_
 
image_transport::Publisher left_rgb_cam_pub_
 
sensor_msgs::Image left_rgb_image_
 
ros::Publisher left_rgb_rect_cam_info_pub_
 
image_transport::CameraPublisher left_rgb_rect_cam_pub_
 
sensor_msgs::Image left_rgb_rect_image_
 
image_transport::ImageTransport left_rgb_rect_transport_
 
image_transport::ImageTransport left_rgb_transport_
 
stereo_msgs::DisparityImage left_stereo_disparity_
 
ros::Publisher left_stereo_disparity_pub_
 
sensor_msgs::PointCloud2 luma_organized_point_cloud_
 
ros::Publisher luma_organized_point_cloud_pub_
 
sensor_msgs::PointCloud2 luma_point_cloud_
 
ros::Publisher luma_point_cloud_pub_
 
image_transport::Publisher ni_depth_cam_pub_
 
sensor_msgs::Image ni_depth_image_
 
image_transport::ImageTransport ni_depth_transport_
 
std::vector< uint8_t > pointcloud_color_buffer_
 
double pointcloud_max_range_ = 15.0
 
std::vector< uint8_t > pointcloud_rect_color_buffer_
 
int32_t ptp_time_offset_secs_ = 0
 
std::atomic_bool ptp_time_sync_ {false}
 
ros::Publisher raw_cam_cal_pub_
 
ros::Publisher raw_cam_config_pub_
 
multisense_ros::RawCamData raw_cam_data_
 
ros::Publisher raw_cam_data_pub_
 
ros::Publisher right_disp_cam_info_pub_
 
sensor_msgs::Image right_disparity_image_
 
image_transport::Publisher right_disparity_pub_
 
ros::Publisher right_mono_cam_info_pub_
 
image_transport::Publisher right_mono_cam_pub_
 
sensor_msgs::Image right_mono_image_
 
image_transport::ImageTransport right_mono_transport_
 
ros::NodeHandle right_nh_
 
ros::Publisher right_rect_cam_info_pub_
 
image_transport::CameraPublisher right_rect_cam_pub_
 
sensor_msgs::Image right_rect_image_
 
image_transport::ImageTransport right_rect_transport_
 
stereo_msgs::DisparityImage right_stereo_disparity_
 
ros::Publisher right_stereo_disparity_pub_
 
ground_surface_utilities::SplineDrawParameters spline_draw_params_
 
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
 
std::shared_ptr< StereoCalibrationManagerstereo_calibration_manager_
 
std::mutex stream_lock_
 
StreamMapType stream_map_
 
crl::multisense::system::VersionInfo version_info_
 

Static Private Attributes

static constexpr char AUX [] = "aux"
 
static constexpr char AUX_CAMERA_FRAME [] = "/aux_camera_frame"
 
static constexpr char AUX_RECTIFIED_FRAME [] = "/aux_camera_optical_frame"
 
static constexpr char CALIBRATION [] = "calibration"
 
static constexpr char COLOR_CAMERA_INFO_TOPIC [] = "image_color/camera_info"
 
static constexpr char COLOR_ORGANIZED_POINTCLOUD_TOPIC [] = "organized_image_points2_color"
 
static constexpr char COLOR_POINTCLOUD_TOPIC [] = "image_points2_color"
 
static constexpr char COLOR_TOPIC [] = "image_color"
 
static constexpr char COST_CAMERA_INFO_TOPIC [] = "cost/camera_info"
 
static constexpr char COST_TOPIC [] = "cost"
 
static constexpr char DEPTH_CAMERA_INFO_TOPIC [] = "depth/camera_info"
 
static constexpr char DEPTH_TOPIC [] = "depth"
 
static constexpr char DEVICE_INFO_TOPIC [] = "device_info"
 
static constexpr char DISPARITY_CAMERA_INFO_TOPIC [] = "disparity/camera_info"
 
static constexpr char DISPARITY_IMAGE_TOPIC [] = "disparity_image"
 
static constexpr char DISPARITY_TOPIC [] = "disparity"
 
static constexpr char GROUND_SURFACE [] = "ground_surface"
 
static constexpr char GROUND_SURFACE_IMAGE_TOPIC [] = "image"
 
static constexpr char GROUND_SURFACE_INFO_TOPIC [] = "camera_info"
 
static constexpr char GROUND_SURFACE_POINT_SPLINE_TOPIC [] = "spline"
 
static constexpr char HEAD_FRAME [] = "/head"
 
static constexpr char HISTOGRAM_TOPIC [] = "histogram"
 
static constexpr char LEFT [] = "left"
 
static constexpr char LEFT_CAMERA_FRAME [] = "/left_camera_frame"
 
static constexpr char LEFT_RECTIFIED_FRAME [] = "/left_camera_optical_frame"
 
static constexpr char MONO_CAMERA_INFO_TOPIC [] = "image_mono/camera_info"
 
static constexpr char MONO_TOPIC [] = "image_mono"
 
static constexpr char OPENNI_DEPTH_TOPIC [] = "openni_depth"
 
static constexpr char ORGANIZED_POINTCLOUD_TOPIC [] = "organized_image_points2"
 
static constexpr char ORIGIN_FRAME [] = "/origin"
 
static constexpr char POINTCLOUD_TOPIC [] = "image_points2"
 
static constexpr char RAW_CAM_CAL_TOPIC [] = "raw_cam_cal"
 
static constexpr char RAW_CAM_CONFIG_TOPIC [] = "raw_cam_config"
 
static constexpr char RAW_CAM_DATA_TOPIC [] = "raw_cam_data"
 
static constexpr char RECT_CAMERA_INFO_TOPIC [] = "image_rect/camera_info"
 
static constexpr char RECT_COLOR_CAMERA_INFO_TOPIC [] = "image_rect_color/camera_info"
 
static constexpr char RECT_COLOR_TOPIC [] = "image_rect_color"
 
static constexpr char RECT_TOPIC [] = "image_rect"
 
static constexpr char RIGHT [] = "right"
 
static constexpr char RIGHT_CAMERA_FRAME [] = "/right_camera_frame"
 
static constexpr char RIGHT_RECTIFIED_FRAME [] = "/right_camera_optical_frame"
 

Detailed Description

Definition at line 60 of file camera.h.

Member Typedef Documentation

◆ StreamMapType

Definition at line 315 of file camera.h.

Constructor & Destructor Documentation

◆ Camera()

multisense_ros::Camera::Camera ( crl::multisense::Channel driver,
const std::string &  tf_prefix 
)

Definition at line 167 of file camera.cpp.

◆ ~Camera()

multisense_ros::Camera::~Camera ( )

Definition at line 728 of file camera.cpp.

Member Function Documentation

◆ borderClipChanged()

void multisense_ros::Camera::borderClipChanged ( const BorderClip borderClipType,
double  borderClipValue 
)

Definition at line 764 of file camera.cpp.

◆ colorImageCallback()

void multisense_ros::Camera::colorImageCallback ( const crl::multisense::image::Header header)

Definition at line 1872 of file camera.cpp.

◆ colorizeCallback()

void multisense_ros::Camera::colorizeCallback ( const crl::multisense::image::Header header)

Definition at line 2061 of file camera.cpp.

◆ connectStream()

void multisense_ros::Camera::connectStream ( crl::multisense::DataSource  enableMask)
private

Definition at line 2443 of file camera.cpp.

◆ convertImageTimestamp()

ros::Time multisense_ros::Camera::convertImageTimestamp ( uint32_t  time_secs,
uint32_t  time_microsecs 
)
private

Definition at line 2191 of file camera.cpp.

◆ depthCallback()

void multisense_ros::Camera::depthCallback ( const crl::multisense::image::Header header)

Definition at line 1348 of file camera.cpp.

◆ deviceInfoDiagnostic()

void multisense_ros::Camera::deviceInfoDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 2241 of file camera.cpp.

◆ deviceStatusDiagnostic()

void multisense_ros::Camera::deviceStatusDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 2284 of file camera.cpp.

◆ diagnosticTimerCallback()

void multisense_ros::Camera::diagnosticTimerCallback ( const ros::TimerEvent )
private

Definition at line 2341 of file camera.cpp.

◆ disconnectStream()

void multisense_ros::Camera::disconnectStream ( crl::multisense::DataSource  disableMask)
private

Definition at line 2462 of file camera.cpp.

◆ disparityImageCallback()

void multisense_ros::Camera::disparityImageCallback ( const crl::multisense::image::Header header)

Definition at line 920 of file camera.cpp.

◆ extrinsicsChanged()

void multisense_ros::Camera::extrinsicsChanged ( crl::multisense::system::ExternalCalibration  extrinsics)

Definition at line 784 of file camera.cpp.

◆ groundSurfaceCallback()

void multisense_ros::Camera::groundSurfaceCallback ( const crl::multisense::image::Header header)

Definition at line 2076 of file camera.cpp.

◆ groundSurfaceSplineCallback()

void multisense_ros::Camera::groundSurfaceSplineCallback ( const crl::multisense::ground_surface::Header header)

Definition at line 2145 of file camera.cpp.

◆ groundSurfaceSplineDrawParametersChanged()

void multisense_ros::Camera::groundSurfaceSplineDrawParametersChanged ( const ground_surface_utilities::SplineDrawParameters spline_draw_params)

Definition at line 814 of file camera.cpp.

◆ histogramCallback()

void multisense_ros::Camera::histogramCallback ( const crl::multisense::image::Header header)

Definition at line 820 of file camera.cpp.

◆ jpegImageCallback()

void multisense_ros::Camera::jpegImageCallback ( const crl::multisense::image::Header header)

Definition at line 855 of file camera.cpp.

◆ maxPointCloudRangeChanged()

void multisense_ros::Camera::maxPointCloudRangeChanged ( double  range)

Definition at line 773 of file camera.cpp.

◆ monoCallback()

void multisense_ros::Camera::monoCallback ( const crl::multisense::image::Header header)

Definition at line 1105 of file camera.cpp.

◆ pointCloudCallback()

void multisense_ros::Camera::pointCloudCallback ( const crl::multisense::image::Header header)

Definition at line 1493 of file camera.cpp.

◆ ptpStatusDiagnostic()

void multisense_ros::Camera::ptpStatusDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 2315 of file camera.cpp.

◆ publishAllCameraInfo()

void multisense_ros::Camera::publishAllCameraInfo ( )
private

Definition at line 2346 of file camera.cpp.

◆ rawCamDataCallback()

void multisense_ros::Camera::rawCamDataCallback ( const crl::multisense::image::Header header)

Definition at line 1831 of file camera.cpp.

◆ rectCallback()

void multisense_ros::Camera::rectCallback ( const crl::multisense::image::Header header)

Definition at line 1217 of file camera.cpp.

◆ stop()

void multisense_ros::Camera::stop ( )
private

Definition at line 2431 of file camera.cpp.

◆ timeSyncChanged()

void multisense_ros::Camera::timeSyncChanged ( bool  ptp_enabled,
int32_t  ptp_time_offset_sec 
)

Definition at line 778 of file camera.cpp.

◆ updateConfig()

void multisense_ros::Camera::updateConfig ( const crl::multisense::image::Config config)

Definition at line 2202 of file camera.cpp.

Member Data Documentation

◆ AUX

constexpr char multisense_ros::Camera::AUX = "aux"
staticconstexprprivate

Definition at line 98 of file camera.h.

◆ AUX_CAMERA_FRAME

constexpr char multisense_ros::Camera::AUX_CAMERA_FRAME = "/aux_camera_frame"
staticconstexprprivate

Definition at line 111 of file camera.h.

◆ aux_mono_cam_info_pub_

ros::Publisher multisense_ros::Camera::aux_mono_cam_info_pub_
private

Definition at line 222 of file camera.h.

◆ aux_mono_cam_pub_

image_transport::Publisher multisense_ros::Camera::aux_mono_cam_pub_
private

Definition at line 207 of file camera.h.

◆ aux_mono_image_

sensor_msgs::Image multisense_ros::Camera::aux_mono_image_
private

Definition at line 265 of file camera.h.

◆ aux_mono_transport_

image_transport::ImageTransport multisense_ros::Camera::aux_mono_transport_
private

Definition at line 189 of file camera.h.

◆ aux_nh_

ros::NodeHandle multisense_ros::Camera::aux_nh_
private

Definition at line 171 of file camera.h.

◆ aux_rect_cam_info_pub_

ros::Publisher multisense_ros::Camera::aux_rect_cam_info_pub_
private

Definition at line 224 of file camera.h.

◆ aux_rect_cam_pub_

image_transport::CameraPublisher multisense_ros::Camera::aux_rect_cam_pub_
private

Definition at line 208 of file camera.h.

◆ aux_rect_image_

sensor_msgs::Image multisense_ros::Camera::aux_rect_image_
private

Definition at line 269 of file camera.h.

◆ aux_rect_transport_

image_transport::ImageTransport multisense_ros::Camera::aux_rect_transport_
private

Definition at line 191 of file camera.h.

◆ AUX_RECTIFIED_FRAME

constexpr char multisense_ros::Camera::AUX_RECTIFIED_FRAME = "/aux_camera_optical_frame"
staticconstexprprivate

Definition at line 112 of file camera.h.

◆ aux_rgb_cam_info_pub_

ros::Publisher multisense_ros::Camera::aux_rgb_cam_info_pub_
private

Definition at line 223 of file camera.h.

◆ aux_rgb_cam_pub_

image_transport::Publisher multisense_ros::Camera::aux_rgb_cam_pub_
private

Definition at line 206 of file camera.h.

◆ aux_rgb_image_

sensor_msgs::Image multisense_ros::Camera::aux_rgb_image_
private

Definition at line 267 of file camera.h.

◆ aux_rgb_rect_cam_info_pub_

ros::Publisher multisense_ros::Camera::aux_rgb_rect_cam_info_pub_
private

Definition at line 225 of file camera.h.

◆ aux_rgb_rect_cam_pub_

image_transport::CameraPublisher multisense_ros::Camera::aux_rgb_rect_cam_pub_
private

Definition at line 209 of file camera.h.

◆ aux_rgb_rect_image_

sensor_msgs::Image multisense_ros::Camera::aux_rgb_rect_image_
private

Definition at line 270 of file camera.h.

◆ aux_rgb_rect_transport_

image_transport::ImageTransport multisense_ros::Camera::aux_rgb_rect_transport_
private

Definition at line 192 of file camera.h.

◆ aux_rgb_transport_

image_transport::ImageTransport multisense_ros::Camera::aux_rgb_transport_
private

Definition at line 190 of file camera.h.

◆ border_clip_type_

BorderClip multisense_ros::Camera::border_clip_type_ = BorderClip::NONE
private

Definition at line 332 of file camera.h.

◆ border_clip_value_

double multisense_ros::Camera::border_clip_value_ = 0.0
private

Definition at line 333 of file camera.h.

◆ CALIBRATION

constexpr char multisense_ros::Camera::CALIBRATION = "calibration"
staticconstexprprivate

Definition at line 99 of file camera.h.

◆ calibration_nh_

ros::NodeHandle multisense_ros::Camera::calibration_nh_
private

Definition at line 172 of file camera.h.

◆ can_support_ground_surface_

bool multisense_ros::Camera::can_support_ground_surface_ = false
private

Definition at line 368 of file camera.h.

◆ COLOR_CAMERA_INFO_TOPIC

constexpr char multisense_ros::Camera::COLOR_CAMERA_INFO_TOPIC = "image_color/camera_info"
staticconstexprprivate

Definition at line 137 of file camera.h.

◆ color_organized_point_cloud_

sensor_msgs::PointCloud2 multisense_ros::Camera::color_organized_point_cloud_
private

Definition at line 263 of file camera.h.

◆ color_organized_point_cloud_pub_

ros::Publisher multisense_ros::Camera::color_organized_point_cloud_pub_
private

Definition at line 233 of file camera.h.

◆ COLOR_ORGANIZED_POINTCLOUD_TOPIC

constexpr char multisense_ros::Camera::COLOR_ORGANIZED_POINTCLOUD_TOPIC = "organized_image_points2_color"
staticconstexprprivate

Definition at line 134 of file camera.h.

◆ color_point_cloud_

sensor_msgs::PointCloud2 multisense_ros::Camera::color_point_cloud_
private

Definition at line 261 of file camera.h.

◆ color_point_cloud_pub_

ros::Publisher multisense_ros::Camera::color_point_cloud_pub_
private

Definition at line 229 of file camera.h.

◆ COLOR_POINTCLOUD_TOPIC

constexpr char multisense_ros::Camera::COLOR_POINTCLOUD_TOPIC = "image_points2_color"
staticconstexprprivate

Definition at line 132 of file camera.h.

◆ COLOR_TOPIC

constexpr char multisense_ros::Camera::COLOR_TOPIC = "image_color"
staticconstexprprivate

Definition at line 129 of file camera.h.

◆ COST_CAMERA_INFO_TOPIC

constexpr char multisense_ros::Camera::COST_CAMERA_INFO_TOPIC = "cost/camera_info"
staticconstexprprivate

Definition at line 141 of file camera.h.

◆ COST_TOPIC

constexpr char multisense_ros::Camera::COST_TOPIC = "cost"
staticconstexprprivate

Definition at line 128 of file camera.h.

◆ depth_cam_info_pub_

ros::Publisher multisense_ros::Camera::depth_cam_info_pub_
private

Definition at line 221 of file camera.h.

◆ depth_cam_pub_

image_transport::Publisher multisense_ros::Camera::depth_cam_pub_
private

Definition at line 202 of file camera.h.

◆ DEPTH_CAMERA_INFO_TOPIC

constexpr char multisense_ros::Camera::DEPTH_CAMERA_INFO_TOPIC = "depth/camera_info"
staticconstexprprivate

Definition at line 139 of file camera.h.

◆ depth_image_

sensor_msgs::Image multisense_ros::Camera::depth_image_
private

Definition at line 258 of file camera.h.

◆ DEPTH_TOPIC

constexpr char multisense_ros::Camera::DEPTH_TOPIC = "depth"
staticconstexprprivate

Definition at line 126 of file camera.h.

◆ depth_transport_

image_transport::ImageTransport multisense_ros::Camera::depth_transport_
private

Definition at line 184 of file camera.h.

◆ device_info_

crl::multisense::system::DeviceInfo multisense_ros::Camera::device_info_
private

Definition at line 290 of file camera.h.

◆ device_info_pub_

ros::Publisher multisense_ros::Camera::device_info_pub_
private

Definition at line 248 of file camera.h.

◆ DEVICE_INFO_TOPIC

constexpr char multisense_ros::Camera::DEVICE_INFO_TOPIC = "device_info"
staticconstexprprivate

Definition at line 117 of file camera.h.

◆ device_modes_

std::vector<crl::multisense::system::DeviceMode> multisense_ros::Camera::device_modes_
private

Definition at line 291 of file camera.h.

◆ device_nh_

ros::NodeHandle multisense_ros::Camera::device_nh_
private

Definition at line 168 of file camera.h.

◆ diagnostic_trigger_

ros::Timer multisense_ros::Camera::diagnostic_trigger_
private

Definition at line 378 of file camera.h.

◆ diagnostic_updater_

diagnostic_updater::Updater multisense_ros::Camera::diagnostic_updater_
private

Definition at line 372 of file camera.h.

◆ DISPARITY_CAMERA_INFO_TOPIC

constexpr char multisense_ros::Camera::DISPARITY_CAMERA_INFO_TOPIC = "disparity/camera_info"
staticconstexprprivate

Definition at line 140 of file camera.h.

◆ disparity_cost_transport_

image_transport::ImageTransport multisense_ros::Camera::disparity_cost_transport_
private

Definition at line 188 of file camera.h.

◆ DISPARITY_IMAGE_TOPIC

constexpr char multisense_ros::Camera::DISPARITY_IMAGE_TOPIC = "disparity_image"
staticconstexprprivate

Definition at line 125 of file camera.h.

◆ disparity_left_transport_

image_transport::ImageTransport multisense_ros::Camera::disparity_left_transport_
private

Definition at line 186 of file camera.h.

◆ disparity_right_transport_

image_transport::ImageTransport multisense_ros::Camera::disparity_right_transport_
private

Definition at line 187 of file camera.h.

◆ DISPARITY_TOPIC

constexpr char multisense_ros::Camera::DISPARITY_TOPIC = "disparity"
staticconstexprprivate

Definition at line 124 of file camera.h.

◆ driver_

crl::multisense::Channel* multisense_ros::Camera::driver_ = nullptr
private

Definition at line 163 of file camera.h.

◆ frame_id_aux_

const std::string multisense_ros::Camera::frame_id_aux_
private

Definition at line 305 of file camera.h.

◆ frame_id_head_

const std::string multisense_ros::Camera::frame_id_head_
private

Definition at line 302 of file camera.h.

◆ frame_id_left_

const std::string multisense_ros::Camera::frame_id_left_
private

Definition at line 303 of file camera.h.

◆ frame_id_origin_

const std::string multisense_ros::Camera::frame_id_origin_
private

Definition at line 301 of file camera.h.

◆ frame_id_rectified_aux_

const std::string multisense_ros::Camera::frame_id_rectified_aux_
private

Definition at line 308 of file camera.h.

◆ frame_id_rectified_left_

const std::string multisense_ros::Camera::frame_id_rectified_left_
private

Definition at line 306 of file camera.h.

◆ frame_id_rectified_right_

const std::string multisense_ros::Camera::frame_id_rectified_right_
private

Definition at line 307 of file camera.h.

◆ frame_id_right_

const std::string multisense_ros::Camera::frame_id_right_
private

Definition at line 304 of file camera.h.

◆ GROUND_SURFACE

constexpr char multisense_ros::Camera::GROUND_SURFACE = "ground_surface"
staticconstexprprivate

Definition at line 100 of file camera.h.

◆ ground_surface_cam_pub_

image_transport::Publisher multisense_ros::Camera::ground_surface_cam_pub_
private

Definition at line 210 of file camera.h.

◆ ground_surface_image_

sensor_msgs::Image multisense_ros::Camera::ground_surface_image_
private

Definition at line 279 of file camera.h.

◆ GROUND_SURFACE_IMAGE_TOPIC

constexpr char multisense_ros::Camera::GROUND_SURFACE_IMAGE_TOPIC = "image"
staticconstexprprivate

Definition at line 142 of file camera.h.

◆ ground_surface_info_pub_

ros::Publisher multisense_ros::Camera::ground_surface_info_pub_
private

Definition at line 226 of file camera.h.

◆ GROUND_SURFACE_INFO_TOPIC

constexpr char multisense_ros::Camera::GROUND_SURFACE_INFO_TOPIC = "camera_info"
staticconstexprprivate

Definition at line 143 of file camera.h.

◆ ground_surface_nh_

ros::NodeHandle multisense_ros::Camera::ground_surface_nh_
private

Definition at line 173 of file camera.h.

◆ GROUND_SURFACE_POINT_SPLINE_TOPIC

constexpr char multisense_ros::Camera::GROUND_SURFACE_POINT_SPLINE_TOPIC = "spline"
staticconstexprprivate

Definition at line 144 of file camera.h.

◆ ground_surface_spline_pub_

ros::Publisher multisense_ros::Camera::ground_surface_spline_pub_
private

Definition at line 230 of file camera.h.

◆ ground_surface_transport_

image_transport::ImageTransport multisense_ros::Camera::ground_surface_transport_
private

Definition at line 193 of file camera.h.

◆ has_aux_camera_

bool multisense_ros::Camera::has_aux_camera_ = false
private

Definition at line 358 of file camera.h.

◆ has_color_

bool multisense_ros::Camera::has_color_ = false
private

Definition at line 363 of file camera.h.

◆ has_left_camera_

bool multisense_ros::Camera::has_left_camera_ = false
private

Definition at line 353 of file camera.h.

◆ has_right_camera_

bool multisense_ros::Camera::has_right_camera_ = false
private

Definition at line 348 of file camera.h.

◆ HEAD_FRAME

constexpr char multisense_ros::Camera::HEAD_FRAME = "/head"
staticconstexprprivate

Definition at line 106 of file camera.h.

◆ histogram_pub_

ros::Publisher multisense_ros::Camera::histogram_pub_
private

Definition at line 249 of file camera.h.

◆ HISTOGRAM_TOPIC

constexpr char multisense_ros::Camera::HISTOGRAM_TOPIC = "histogram"
staticconstexprprivate

Definition at line 121 of file camera.h.

◆ image_buffers_

std::unordered_map<crl::multisense::DataSource, std::shared_ptr<BufferWrapper<crl::multisense::image::Header> > > multisense_ros::Camera::image_buffers_
private

Definition at line 343 of file camera.h.

◆ last_frame_id_

int64_t multisense_ros::Camera::last_frame_id_ = -1
private

Definition at line 327 of file camera.h.

◆ LEFT

constexpr char multisense_ros::Camera::LEFT = "left"
staticconstexprprivate

Definition at line 96 of file camera.h.

◆ LEFT_CAMERA_FRAME

constexpr char multisense_ros::Camera::LEFT_CAMERA_FRAME = "/left_camera_frame"
staticconstexprprivate

Definition at line 107 of file camera.h.

◆ left_cost_cam_info_pub_

ros::Publisher multisense_ros::Camera::left_cost_cam_info_pub_
private

Definition at line 218 of file camera.h.

◆ left_disp_cam_info_pub_

ros::Publisher multisense_ros::Camera::left_disp_cam_info_pub_
private

Definition at line 216 of file camera.h.

◆ left_disparity_cost_image_

sensor_msgs::Image multisense_ros::Camera::left_disparity_cost_image_
private

Definition at line 273 of file camera.h.

◆ left_disparity_cost_pub_

image_transport::Publisher multisense_ros::Camera::left_disparity_cost_pub_
private

Definition at line 237 of file camera.h.

◆ left_disparity_image_

sensor_msgs::Image multisense_ros::Camera::left_disparity_image_
private

Definition at line 272 of file camera.h.

◆ left_disparity_pub_

image_transport::Publisher multisense_ros::Camera::left_disparity_pub_
private

Definition at line 235 of file camera.h.

◆ left_mono_cam_info_pub_

ros::Publisher multisense_ros::Camera::left_mono_cam_info_pub_
private

Definition at line 212 of file camera.h.

◆ left_mono_cam_pub_

image_transport::Publisher multisense_ros::Camera::left_mono_cam_pub_
private

Definition at line 198 of file camera.h.

◆ left_mono_image_

sensor_msgs::Image multisense_ros::Camera::left_mono_image_
private

Definition at line 254 of file camera.h.

◆ left_mono_transport_

image_transport::ImageTransport multisense_ros::Camera::left_mono_transport_
private

Definition at line 178 of file camera.h.

◆ left_nh_

ros::NodeHandle multisense_ros::Camera::left_nh_
private

Definition at line 169 of file camera.h.

◆ left_rect_cam_info_pub_

ros::Publisher multisense_ros::Camera::left_rect_cam_info_pub_
private

Definition at line 214 of file camera.h.

◆ left_rect_cam_pub_

image_transport::CameraPublisher multisense_ros::Camera::left_rect_cam_pub_
private

Definition at line 200 of file camera.h.

◆ left_rect_image_

sensor_msgs::Image multisense_ros::Camera::left_rect_image_
private

Definition at line 256 of file camera.h.

◆ left_rect_transport_

image_transport::ImageTransport multisense_ros::Camera::left_rect_transport_
private

Definition at line 180 of file camera.h.

◆ LEFT_RECTIFIED_FRAME

constexpr char multisense_ros::Camera::LEFT_RECTIFIED_FRAME = "/left_camera_optical_frame"
staticconstexprprivate

Definition at line 108 of file camera.h.

◆ left_rgb_cam_info_pub_

ros::Publisher multisense_ros::Camera::left_rgb_cam_info_pub_
private

Definition at line 219 of file camera.h.

◆ left_rgb_cam_pub_

image_transport::Publisher multisense_ros::Camera::left_rgb_cam_pub_
private

Definition at line 204 of file camera.h.

◆ left_rgb_image_

sensor_msgs::Image multisense_ros::Camera::left_rgb_image_
private

Definition at line 266 of file camera.h.

◆ left_rgb_rect_cam_info_pub_

ros::Publisher multisense_ros::Camera::left_rgb_rect_cam_info_pub_
private

Definition at line 220 of file camera.h.

◆ left_rgb_rect_cam_pub_

image_transport::CameraPublisher multisense_ros::Camera::left_rgb_rect_cam_pub_
private

Definition at line 205 of file camera.h.

◆ left_rgb_rect_image_

sensor_msgs::Image multisense_ros::Camera::left_rgb_rect_image_
private

Definition at line 268 of file camera.h.

◆ left_rgb_rect_transport_

image_transport::ImageTransport multisense_ros::Camera::left_rgb_rect_transport_
private

Definition at line 183 of file camera.h.

◆ left_rgb_transport_

image_transport::ImageTransport multisense_ros::Camera::left_rgb_transport_
private

Definition at line 182 of file camera.h.

◆ left_stereo_disparity_

stereo_msgs::DisparityImage multisense_ros::Camera::left_stereo_disparity_
private

Definition at line 276 of file camera.h.

◆ left_stereo_disparity_pub_

ros::Publisher multisense_ros::Camera::left_stereo_disparity_pub_
private

Definition at line 239 of file camera.h.

◆ luma_organized_point_cloud_

sensor_msgs::PointCloud2 multisense_ros::Camera::luma_organized_point_cloud_
private

Definition at line 262 of file camera.h.

◆ luma_organized_point_cloud_pub_

ros::Publisher multisense_ros::Camera::luma_organized_point_cloud_pub_
private

Definition at line 232 of file camera.h.

◆ luma_point_cloud_

sensor_msgs::PointCloud2 multisense_ros::Camera::luma_point_cloud_
private

Definition at line 260 of file camera.h.

◆ luma_point_cloud_pub_

ros::Publisher multisense_ros::Camera::luma_point_cloud_pub_
private

Definition at line 228 of file camera.h.

◆ MONO_CAMERA_INFO_TOPIC

constexpr char multisense_ros::Camera::MONO_CAMERA_INFO_TOPIC = "image_mono/camera_info"
staticconstexprprivate

Definition at line 135 of file camera.h.

◆ MONO_TOPIC

constexpr char multisense_ros::Camera::MONO_TOPIC = "image_mono"
staticconstexprprivate

Definition at line 122 of file camera.h.

◆ ni_depth_cam_pub_

image_transport::Publisher multisense_ros::Camera::ni_depth_cam_pub_
private

Definition at line 203 of file camera.h.

◆ ni_depth_image_

sensor_msgs::Image multisense_ros::Camera::ni_depth_image_
private

Definition at line 259 of file camera.h.

◆ ni_depth_transport_

image_transport::ImageTransport multisense_ros::Camera::ni_depth_transport_
private

Definition at line 185 of file camera.h.

◆ OPENNI_DEPTH_TOPIC

constexpr char multisense_ros::Camera::OPENNI_DEPTH_TOPIC = "openni_depth"
staticconstexprprivate

Definition at line 127 of file camera.h.

◆ ORGANIZED_POINTCLOUD_TOPIC

constexpr char multisense_ros::Camera::ORGANIZED_POINTCLOUD_TOPIC = "organized_image_points2"
staticconstexprprivate

Definition at line 133 of file camera.h.

◆ ORIGIN_FRAME

constexpr char multisense_ros::Camera::ORIGIN_FRAME = "/origin"
staticconstexprprivate

Definition at line 105 of file camera.h.

◆ pointcloud_color_buffer_

std::vector<uint8_t> multisense_ros::Camera::pointcloud_color_buffer_
private

Definition at line 283 of file camera.h.

◆ pointcloud_max_range_

double multisense_ros::Camera::pointcloud_max_range_ = 15.0
private

Definition at line 322 of file camera.h.

◆ pointcloud_rect_color_buffer_

std::vector<uint8_t> multisense_ros::Camera::pointcloud_rect_color_buffer_
private

Definition at line 284 of file camera.h.

◆ POINTCLOUD_TOPIC

constexpr char multisense_ros::Camera::POINTCLOUD_TOPIC = "image_points2"
staticconstexprprivate

Definition at line 131 of file camera.h.

◆ ptp_time_offset_secs_

int32_t multisense_ros::Camera::ptp_time_offset_secs_ = 0
private

Definition at line 385 of file camera.h.

◆ ptp_time_sync_

std::atomic_bool multisense_ros::Camera::ptp_time_sync_ {false}
private

Definition at line 384 of file camera.h.

◆ raw_cam_cal_pub_

ros::Publisher multisense_ros::Camera::raw_cam_cal_pub_
private

Definition at line 247 of file camera.h.

◆ RAW_CAM_CAL_TOPIC

constexpr char multisense_ros::Camera::RAW_CAM_CAL_TOPIC = "raw_cam_cal"
staticconstexprprivate

Definition at line 118 of file camera.h.

◆ raw_cam_config_pub_

ros::Publisher multisense_ros::Camera::raw_cam_config_pub_
private

Definition at line 246 of file camera.h.

◆ RAW_CAM_CONFIG_TOPIC

constexpr char multisense_ros::Camera::RAW_CAM_CONFIG_TOPIC = "raw_cam_config"
staticconstexprprivate

Definition at line 119 of file camera.h.

◆ raw_cam_data_

multisense_ros::RawCamData multisense_ros::Camera::raw_cam_data_
private

Definition at line 281 of file camera.h.

◆ raw_cam_data_pub_

ros::Publisher multisense_ros::Camera::raw_cam_data_pub_
private

Definition at line 245 of file camera.h.

◆ RAW_CAM_DATA_TOPIC

constexpr char multisense_ros::Camera::RAW_CAM_DATA_TOPIC = "raw_cam_data"
staticconstexprprivate

Definition at line 120 of file camera.h.

◆ RECT_CAMERA_INFO_TOPIC

constexpr char multisense_ros::Camera::RECT_CAMERA_INFO_TOPIC = "image_rect/camera_info"
staticconstexprprivate

Definition at line 136 of file camera.h.

◆ RECT_COLOR_CAMERA_INFO_TOPIC

constexpr char multisense_ros::Camera::RECT_COLOR_CAMERA_INFO_TOPIC = "image_rect_color/camera_info"
staticconstexprprivate

Definition at line 138 of file camera.h.

◆ RECT_COLOR_TOPIC

constexpr char multisense_ros::Camera::RECT_COLOR_TOPIC = "image_rect_color"
staticconstexprprivate

Definition at line 130 of file camera.h.

◆ RECT_TOPIC

constexpr char multisense_ros::Camera::RECT_TOPIC = "image_rect"
staticconstexprprivate

Definition at line 123 of file camera.h.

◆ RIGHT

constexpr char multisense_ros::Camera::RIGHT = "right"
staticconstexprprivate

Definition at line 97 of file camera.h.

◆ RIGHT_CAMERA_FRAME

constexpr char multisense_ros::Camera::RIGHT_CAMERA_FRAME = "/right_camera_frame"
staticconstexprprivate

Definition at line 109 of file camera.h.

◆ right_disp_cam_info_pub_

ros::Publisher multisense_ros::Camera::right_disp_cam_info_pub_
private

Definition at line 217 of file camera.h.

◆ right_disparity_image_

sensor_msgs::Image multisense_ros::Camera::right_disparity_image_
private

Definition at line 274 of file camera.h.

◆ right_disparity_pub_

image_transport::Publisher multisense_ros::Camera::right_disparity_pub_
private

Definition at line 236 of file camera.h.

◆ right_mono_cam_info_pub_

ros::Publisher multisense_ros::Camera::right_mono_cam_info_pub_
private

Definition at line 213 of file camera.h.

◆ right_mono_cam_pub_

image_transport::Publisher multisense_ros::Camera::right_mono_cam_pub_
private

Definition at line 199 of file camera.h.

◆ right_mono_image_

sensor_msgs::Image multisense_ros::Camera::right_mono_image_
private

Definition at line 255 of file camera.h.

◆ right_mono_transport_

image_transport::ImageTransport multisense_ros::Camera::right_mono_transport_
private

Definition at line 179 of file camera.h.

◆ right_nh_

ros::NodeHandle multisense_ros::Camera::right_nh_
private

Definition at line 170 of file camera.h.

◆ right_rect_cam_info_pub_

ros::Publisher multisense_ros::Camera::right_rect_cam_info_pub_
private

Definition at line 215 of file camera.h.

◆ right_rect_cam_pub_

image_transport::CameraPublisher multisense_ros::Camera::right_rect_cam_pub_
private

Definition at line 201 of file camera.h.

◆ right_rect_image_

sensor_msgs::Image multisense_ros::Camera::right_rect_image_
private

Definition at line 257 of file camera.h.

◆ right_rect_transport_

image_transport::ImageTransport multisense_ros::Camera::right_rect_transport_
private

Definition at line 181 of file camera.h.

◆ RIGHT_RECTIFIED_FRAME

constexpr char multisense_ros::Camera::RIGHT_RECTIFIED_FRAME = "/right_camera_optical_frame"
staticconstexprprivate

Definition at line 110 of file camera.h.

◆ right_stereo_disparity_

stereo_msgs::DisparityImage multisense_ros::Camera::right_stereo_disparity_
private

Definition at line 277 of file camera.h.

◆ right_stereo_disparity_pub_

ros::Publisher multisense_ros::Camera::right_stereo_disparity_pub_
private

Definition at line 240 of file camera.h.

◆ spline_draw_params_

ground_surface_utilities::SplineDrawParameters multisense_ros::Camera::spline_draw_params_
private

Definition at line 338 of file camera.h.

◆ static_tf_broadcaster_

tf2_ros::StaticTransformBroadcaster multisense_ros::Camera::static_tf_broadcaster_
private

Definition at line 310 of file camera.h.

◆ stereo_calibration_manager_

std::shared_ptr<StereoCalibrationManager> multisense_ros::Camera::stereo_calibration_manager_
private

Definition at line 296 of file camera.h.

◆ stream_lock_

std::mutex multisense_ros::Camera::stream_lock_
private

Definition at line 316 of file camera.h.

◆ stream_map_

StreamMapType multisense_ros::Camera::stream_map_
private

Definition at line 317 of file camera.h.

◆ version_info_

crl::multisense::system::VersionInfo multisense_ros::Camera::version_info_
private

Definition at line 289 of file camera.h.


The documentation for this class was generated from the following files:


multisense_ros
Author(s):
autogenerated on Thu Apr 17 2025 02:49:25