|
void | clip_depth (rs2::depth_frame depth_frame, float clipping_dist) |
|
sensor_msgs::Imu | CreateUnitedMessage (const CimuData accel_data, const CimuData gyro_data) |
|
void | enable_devices () |
|
void | FillImuData_Copy (const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs) |
|
void | FillImuData_LinearInterpolation (const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs) |
|
cv::Mat & | fix_depth_scale (const cv::Mat &from_image, cv::Mat &to_image) |
|
void | frame_callback (rs2::frame frame) |
|
double | frameSystemTimeSec (rs2::frame frame) |
|
bool | getEnabledProfile (const stream_index_pair &stream_index, rs2::stream_profile &profile) |
|
IMUInfo | getImuInfo (const stream_index_pair &stream_index) |
|
void | getParameters () |
|
void | imu_callback (rs2::frame frame) |
|
void | imu_callback_sync (rs2::frame frame, imu_sync_method sync_method=imu_sync_method::COPY) |
|
void | ImuMessage_AddDefaultValues (sensor_msgs::Imu &imu_msg) |
|
void | monitor_update_functions () |
|
void | multiple_message_callback (rs2::frame frame, imu_sync_method sync_method) |
|
void | pose_callback (rs2::frame frame) |
|
void | publish_frequency_update () |
|
void | publish_temperature () |
|
void | publishAlignedDepthToOthers (rs2::frameset frames, const ros::Time &t) |
|
void | publishDynamicTransforms () |
|
void | publishFrame (rs2::frame f, const ros::Time &t, const stream_index_pair &stream, std::map< stream_index_pair, cv::Mat > &images, const std::map< stream_index_pair, ros::Publisher > &info_publishers, const std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > &image_publishers, std::map< stream_index_pair, int > &seq, std::map< stream_index_pair, sensor_msgs::CameraInfo > &camera_info, const std::map< rs2_stream, std::string > &encoding, bool copy_data_from_frame=true) |
|
void | publishIntrinsics () |
|
void | publishPointCloud (rs2::points f, const ros::Time &t, const rs2::frameset &frameset) |
|
void | publishStaticTransforms () |
|
void | readAndSetDynamicParam (ros::NodeHandle &nh1, std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > ddynrec, const std::string option_name, const int min_val, const int max_val, rs2::sensor sensor, int *option_value) |
|
void | registerAutoExposureROIOptions (ros::NodeHandle &nh) |
|
void | registerDynamicOption (ros::NodeHandle &nh, rs2::options sensor, std::string &module_name) |
|
void | registerHDRoptions () |
|
rs2_stream | rs2_string_to_stream (std::string str) |
|
Extrinsics | rsExtrinsicsToMsg (const rs2_extrinsics &extrinsics, const std::string &frame_id) const |
|
void | runFirstFrameInitialization (rs2_stream stream_type) |
|
void | set_auto_exposure_roi (const std::string option_name, rs2::sensor sensor, int new_value) |
|
void | set_sensor_auto_exposure_roi (rs2::sensor sensor) |
|
void | set_sensor_parameter_to_ros (const std::string &module_name, rs2::options sensor, rs2_option option) |
|
void | SetBaseStream () |
|
bool | setBaseTime (double frame_time, rs2_timestamp_domain time_domain) |
|
void | setupDevice () |
|
void | setupErrorCallback () |
|
void | setupFilters () |
|
void | setupPublishers () |
|
void | setupStreams () |
|
void | startMonitoring () |
|
void | updateStreamCalibData (const rs2::video_stream_profile &video_profile) |
|
|
bool | _allow_no_texture_points |
|
double | _angular_velocity_cov |
|
std::map< std::string, rs2::region_of_interest > | _auto_exposure_roi |
|
stream_index_pair | _base_stream |
|
std::map< stream_index_pair, sensor_msgs::CameraInfo > | _camera_info |
|
double | _camera_time_base |
|
float | _clipping_distance |
|
std::shared_ptr< rs2::filter > | _colorizer |
|
std::condition_variable | _cv_monitoring |
|
std::condition_variable | _cv_tf |
|
std::vector< std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > > | _ddynrec |
|
std::map< stream_index_pair, sensor_msgs::CameraInfo > | _depth_aligned_camera_info |
|
std::map< rs2_stream, std::string > | _depth_aligned_encoding |
|
std::map< stream_index_pair, cv::Mat > | _depth_aligned_image |
|
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > | _depth_aligned_image_publishers |
|
std::map< stream_index_pair, ros::Publisher > | _depth_aligned_info_publisher |
|
std::map< stream_index_pair, int > | _depth_aligned_seq |
|
float | _depth_scale_meters |
|
std::map< stream_index_pair, cv::Mat > | _depth_scaled_image |
|
std::map< stream_index_pair, rs2_extrinsics > | _depth_to_other_extrinsics |
|
std::map< stream_index_pair, ros::Publisher > | _depth_to_other_extrinsics_publishers |
|
rs2::device | _dev |
|
std::vector< rs2::sensor > | _dev_sensors |
|
tf2_ros::TransformBroadcaster | _dynamic_tf_broadcaster |
|
std::map< stream_index_pair, bool > | _enable |
|
std::map< stream_index_pair, std::vector< rs2::stream_profile > > | _enabled_profiles |
|
std::map< rs2_stream, std::string > | _encoding |
|
std::vector< NamedFilter > | _filters |
|
std::string | _filters_str |
|
std::map< rs2_stream, int > | _format |
|
std::map< stream_index_pair, int > | _fps |
|
std::map< stream_index_pair, int > | _height |
|
bool | _hold_back_imu_for_frames |
|
std::map< stream_index_pair, cv::Mat > | _image |
|
std::map< rs2_stream, int > | _image_format |
|
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > | _image_publishers |
|
std::map< stream_index_pair, ros::Publisher > | _imu_publishers |
|
imu_sync_method | _imu_sync_method |
|
std::map< stream_index_pair, ros::Publisher > | _info_publisher |
|
std::map< rs2_stream, bool > | _is_first_frame |
|
std::atomic_bool | _is_initialized_time_base |
|
std::string | _json_file_path |
|
double | _linear_accel_cov |
|
std::shared_ptr< std::thread > | _monitoring_t |
|
sensor_msgs::PointCloud2 | _msg_pointcloud |
|
const std::string | _namespace |
|
bool | _ordered_pc |
|
bool | _pointcloud |
|
std::shared_ptr< rs2::filter > | _pointcloud_filter |
|
ros::Publisher | _pointcloud_publisher |
|
stream_index_pair | _pointcloud_texture |
|
bool | _publish_odom_tf |
|
bool | _publish_tf |
|
ros::Time | _ros_time_base |
|
std::map< stream_index_pair, rs2::sensor > | _sensors |
|
std::map< std::string, std::function< void(rs2::frame)> > | _sensors_callback |
|
std::map< stream_index_pair, int > | _seq |
|
std::string | _serial_no |
|
tf2_ros::StaticTransformBroadcaster | _static_tf_broadcaster |
|
std::vector< geometry_msgs::TransformStamped > | _static_tf_msgs |
|
std::map< stream_index_pair, rs2_intrinsics > | _stream_intrinsics |
|
std::map< rs2_stream, std::string > | _stream_name |
|
bool | _sync_frames |
|
std::shared_ptr< SyncedImuPublisher > | _synced_imu_publisher |
|
PipelineSyncer | _syncer |
|
std::vector< OptionTemperatureDiag > | _temperature_nodes |
|
double | _tf_publish_rate |
|
std::shared_ptr< std::thread > | _tf_t |
|
std::map< rs2_stream, int > | _unit_step_size |
|
std::condition_variable | _update_functions_cv |
|
std::shared_ptr< std::thread > | _update_functions_t |
|
std::vector< std::function< void()> > | _update_functions_v |
|
std::vector< unsigned int > | _valid_pc_indices |
|
std::map< rs2_stream, std::vector< std::function< void()> > > | _video_functions_stack |
|
std::map< stream_index_pair, int > | _width |
|
Definition at line 118 of file base_realsense_node.h.