Skip to content

Commit

Permalink
Options hold weak pointer to sensor, not direct reference
Browse files Browse the repository at this point in the history
  • Loading branch information
OhadMeir committed Jan 4, 2024
1 parent 8bea652 commit 77d1e1c
Show file tree
Hide file tree
Showing 28 changed files with 245 additions and 229 deletions.
6 changes: 3 additions & 3 deletions include/librealsense2/h/rs_option.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,11 @@ extern "C" {
RS2_OPTION_ASIC_TEMPERATURE, /**< Current Asic Temperature */
RS2_OPTION_ERROR_POLLING_ENABLED, /**< disable error handling */
RS2_OPTION_PROJECTOR_TEMPERATURE, /**< Current Projector Temperature */
RS2_OPTION_OUTPUT_TRIGGER_ENABLED, /**< Enable / disable trigger to be outputed from the camera to any external device on every depth frame */
RS2_OPTION_OUTPUT_TRIGGER_ENABLED, /**< Enable / disable trigger to be outputted from the camera to any external device on every depth frame */
RS2_OPTION_MOTION_MODULE_TEMPERATURE, /**< Current Motion-Module Temperature */
RS2_OPTION_DEPTH_UNITS, /**< Number of meters represented by a single depth unit */
RS2_OPTION_ENABLE_MOTION_CORRECTION, /**< Enable/Disable automatic correction of the motion data */
RS2_OPTION_AUTO_EXPOSURE_PRIORITY, /**< Allows sensor to dynamically ajust the frame rate depending on lighting conditions */
RS2_OPTION_AUTO_EXPOSURE_PRIORITY, /**< Allows sensor to dynamically adjust the frame rate depending on lighting conditions */
RS2_OPTION_COLOR_SCHEME, /**< Color scheme for data visualization */
RS2_OPTION_HISTOGRAM_EQUALIZATION_ENABLED, /**< Perform histogram equalization post-processing on the depth data */
RS2_OPTION_MIN_DISTANCE, /**< Minimal distance to the target */
Expand All @@ -62,7 +62,7 @@ extern "C" {
RS2_OPTION_FILTER_SMOOTH_DELTA, /**< 2D-filter range/validity threshold*/
RS2_OPTION_HOLES_FILL, /**< Enhance depth data post-processing with holes filling where appropriate*/
RS2_OPTION_STEREO_BASELINE, /**< The distance in mm between the first and the second imagers in stereo-based depth cameras*/
RS2_OPTION_AUTO_EXPOSURE_CONVERGE_STEP, /**< Allows dynamically ajust the converge step value of the target exposure in Auto-Exposure algorithm*/
RS2_OPTION_AUTO_EXPOSURE_CONVERGE_STEP, /**< Allows dynamically adjust the converge step value of the target exposure in Auto-Exposure algorithm*/
RS2_OPTION_INTER_CAM_SYNC_MODE, /**< Impose Inter-camera HW synchronization mode. Applicable for D400/L500/Rolling Shutter SKUs */
RS2_OPTION_STREAM_FILTER, /**< Select a stream to process */
RS2_OPTION_STREAM_FORMAT_FILTER, /**< Select a stream format to process */
Expand Down
8 changes: 1 addition & 7 deletions src/ds/d400/d400-active.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ namespace librealsense
//PROJECTOR TEMPERATURE OPTION
auto pid = this->_pid;
auto& depth_ep = get_depth_sensor();
auto &raw_depth_ep = get_raw_depth_sensor();

if( pid == ds::RS457_PID )
{
Expand All @@ -44,13 +43,8 @@ namespace librealsense
}
else
{
auto uvc_s = std::dynamic_pointer_cast< uvc_sensor >( raw_depth_ep.shared_from_this() );
if( ! uvc_s )
throw std::runtime_error( "Sensor base is not a uvc sensor" );

depth_ep.register_option( RS2_OPTION_PROJECTOR_TEMPERATURE,
std::make_shared< asic_and_projector_temperature_options >(
std::move( uvc_s ),
std::make_shared< asic_and_projector_temperature_options >( get_raw_depth_sensor(),
RS2_OPTION_PROJECTOR_TEMPERATURE ) );
}
}
Expand Down
7 changes: 3 additions & 4 deletions src/ds/d400/d400-color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -131,7 +131,7 @@ namespace librealsense
void d400_color::init()
{
auto& color_ep = get_color_sensor();
auto& raw_color_ep = get_raw_color_sensor();
auto raw_color_ep = get_raw_color_sensor();

_ds_color_common = std::make_shared<ds_color_common>(raw_color_ep, color_ep, _fw_version, _hw_monitor, this);

Expand All @@ -151,7 +151,6 @@ namespace librealsense
void d400_color::register_options()
{
auto& color_ep = get_color_sensor();
auto& raw_color_ep = get_raw_color_sensor();

if (!val_in_range(_pid, { ds::RS457_PID }))
{
Expand Down Expand Up @@ -222,7 +221,7 @@ namespace librealsense
// attributes of md_capture_stats
auto& color_ep = get_color_sensor();
// attributes of md_rgb_control
auto& raw_color_ep = get_raw_color_sensor();
auto raw_color_ep = get_raw_color_sensor();

if (_pid != ds::RS457_PID)
{
Expand All @@ -231,7 +230,7 @@ namespace librealsense
}
else
{
auto uvc_dev = raw_color_ep.get_uvc_device();
auto uvc_dev = raw_color_ep->get_uvc_device();
if (uvc_dev->is_platform_jetson())
{
// Work-around for discrepancy between the RGB YUYV descriptor and the parser . Use UYUV parser instead
Expand Down
6 changes: 3 additions & 3 deletions src/ds/d400/d400-color.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,10 @@ namespace librealsense
return dynamic_cast<synthetic_sensor&>(get_sensor(_color_device_idx));
}

uvc_sensor& get_raw_color_sensor()
std::shared_ptr< uvc_sensor > get_raw_color_sensor()
{
synthetic_sensor& color_sensor = get_color_sensor();
return dynamic_cast<uvc_sensor&>(*color_sensor.get_raw_sensor());
synthetic_sensor & color_sensor = get_color_sensor();
return std::dynamic_pointer_cast< uvc_sensor >( color_sensor.get_raw_sensor() );
}

protected:
Expand Down
85 changes: 39 additions & 46 deletions src/ds/d400/d400-device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -523,7 +523,7 @@ namespace librealsense
{
using namespace ds;

auto& raw_sensor = get_raw_depth_sensor();
auto raw_sensor = get_raw_depth_sensor();
_pid = group.uvc_devices.front().pid;
// to be changed for D457
bool mipi_sensor = (RS457_PID == _pid);
Expand All @@ -537,16 +537,16 @@ namespace librealsense
{
_hw_monitor = std::make_shared<hw_monitor>(
std::make_shared<locked_transfer>(
std::make_shared<command_transfer_over_xu>(
raw_sensor, depth_xu, DS5_HWMONITOR),
raw_sensor));
std::make_shared<command_transfer_over_xu>( *raw_sensor, depth_xu, DS5_HWMONITOR ),
raw_sensor ) );
}
else
{
if( ! mipi_sensor )
_hw_monitor = std::make_shared< hw_monitor >( std::make_shared< locked_transfer >(
get_backend()->create_usb_device( group.usb_devices.front() ),
raw_sensor ) );
_hw_monitor = std::make_shared< hw_monitor >(
std::make_shared< locked_transfer >(
get_backend()->create_usb_device( group.usb_devices.front() ),
raw_sensor ) );
}
set_hw_monitor_for_auto_calib(_hw_monitor);

Expand Down Expand Up @@ -578,7 +578,7 @@ namespace librealsense
std::vector<uint8_t> gvd_buff(HW_MONITOR_BUFFER_SIZE);

auto& depth_sensor = get_depth_sensor();
auto& raw_depth_sensor = get_raw_depth_sensor();
auto raw_depth_sensor = get_raw_depth_sensor();

using namespace platform;

Expand Down Expand Up @@ -607,7 +607,7 @@ namespace librealsense
usb_modality = (_fw_version >= firmware_version("5.9.8.0"));
if (usb_modality)
{
_usb_mode = raw_depth_sensor.get_usb_specification();
_usb_mode = raw_depth_sensor->get_usb_specification();
if (usb_spec_names.count(_usb_mode) && (usb_undefined != _usb_mode))
usb_type_str = usb_spec_names.at(_usb_mode);
else // Backend fails to provide USB descriptor - occurs with RS3 build. Requires further work
Expand Down Expand Up @@ -648,10 +648,10 @@ namespace librealsense
if ((_pid == RS416_PID || _pid == RS416_RGB_PID) && _fw_version >= firmware_version("5.12.0.1"))
{
depth_sensor.register_option(RS2_OPTION_HARDWARE_PRESET,
std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor, depth_xu, DS5_HARDWARE_PRESET,
"Hardware pipe configuration"));
std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor, depth_xu, DS5_HARDWARE_PRESET,
"Hardware pipe configuration" ) );
depth_sensor.register_option(RS2_OPTION_LED_POWER,
std::make_shared<uvc_xu_option<uint16_t>>(raw_depth_sensor, depth_xu, DS5_LED_PWR,
std::make_shared<uvc_xu_option<uint16_t>>( raw_depth_sensor, depth_xu, DS5_LED_PWR,
"Set the power level of the LED, with 0 meaning LED off"));
}

Expand All @@ -673,23 +673,20 @@ namespace librealsense
else
{
depth_sensor.register_option(RS2_OPTION_OUTPUT_TRIGGER_ENABLED,
std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor, depth_xu, DS5_EXT_TRIGGER,
std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor, depth_xu, DS5_EXT_TRIGGER,
"Generate trigger from the camera to external device once per frame"));

auto uvc_s = std::dynamic_pointer_cast<uvc_sensor>(raw_depth_sensor.shared_from_this());
if (!uvc_s)
throw std::runtime_error("Sensor base is not uvc sensor");

depth_sensor.register_option(RS2_OPTION_ASIC_TEMPERATURE,
std::make_shared<asic_and_projector_temperature_options>(std::move(uvc_s),
RS2_OPTION_ASIC_TEMPERATURE));
std::make_shared< asic_and_projector_temperature_options >( raw_depth_sensor,
RS2_OPTION_ASIC_TEMPERATURE ) );

// D457 dev - get_xu fails for D457 - error polling id not defined
auto error_control = std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor, depth_xu, DS5_ERROR_REPORTING, "Error reporting");
auto error_control = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor, depth_xu,
DS5_ERROR_REPORTING, "Error reporting");

_polling_error_handler = std::make_shared<polling_error_handler>(1000,
error_control,
raw_depth_sensor.get_notifications_processor(),
raw_depth_sensor->get_notifications_processor(),
std::make_shared<ds_notification_decoder>());

depth_sensor.register_option(RS2_OPTION_ERROR_POLLING_ENABLED, std::make_shared<polling_errors_disable>(_polling_error_handler));
Expand All @@ -698,7 +695,7 @@ namespace librealsense

if ((val_in_range(_pid, { RS455_PID })) && (_fw_version >= firmware_version("5.12.11.0")))
{
auto thermal_compensation_toggle = std::make_shared<protected_xu_option<uint8_t>>(raw_depth_sensor, depth_xu,
auto thermal_compensation_toggle = std::make_shared<protected_xu_option<uint8_t>>( raw_depth_sensor, depth_xu,
ds::DS5_THERMAL_COMPENSATION, "Toggle Thermal Compensation Mechanism");

auto temperature_sensor = depth_sensor.get_option_handler(RS2_OPTION_ASIC_TEMPERATURE);
Expand Down Expand Up @@ -730,16 +727,16 @@ namespace librealsense
std::shared_ptr<hdr_option> hdr_enabled_option = nullptr;

//EXPOSURE AND GAIN - preparing uvc options
auto uvc_xu_exposure_option = std::make_shared<uvc_xu_option<uint32_t>>(raw_depth_sensor,
auto uvc_xu_exposure_option = std::make_shared<uvc_xu_option<uint32_t>>( raw_depth_sensor,
depth_xu,
DS5_EXPOSURE,
"Depth Exposure (usec)");
option_range exposure_range = uvc_xu_exposure_option->get_range();
auto uvc_pu_gain_option = std::make_shared<uvc_pu_option>(raw_depth_sensor, RS2_OPTION_GAIN);
auto uvc_pu_gain_option = std::make_shared<uvc_pu_option>( raw_depth_sensor, RS2_OPTION_GAIN);
option_range gain_range = uvc_pu_gain_option->get_range();

//AUTO EXPOSURE
auto enable_auto_exposure = std::make_shared<uvc_xu_option<uint8_t>>(raw_depth_sensor,
auto enable_auto_exposure = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor,
depth_xu,
DS5_ENABLE_AUTO_EXPOSURE,
"Enable Auto Exposure");
Expand Down Expand Up @@ -830,8 +827,8 @@ namespace librealsense
if ((_fw_version >= firmware_version("5.11.3.0")) && ((_device_capabilities & mask) == mask))
{
bool is_fw_version_using_id = (_fw_version >= firmware_version("5.12.8.100"));
auto alternating_emitter_opt = std::make_shared<alternating_emitter_option>(*_hw_monitor, &raw_depth_sensor, is_fw_version_using_id);
auto emitter_always_on_opt = std::make_shared<emitter_always_on_option>(*_hw_monitor, &depth_sensor);
auto alternating_emitter_opt = std::make_shared<alternating_emitter_option>(*_hw_monitor, is_fw_version_using_id);
auto emitter_always_on_opt = std::make_shared<emitter_always_on_option>( *_hw_monitor );

if ((_fw_version >= firmware_version("5.12.1.0")) && ((_device_capabilities & ds_caps::CAP_GLOBAL_SHUTTER) == ds_caps::CAP_GLOBAL_SHUTTER))
{
Expand Down Expand Up @@ -874,17 +871,17 @@ namespace librealsense
if (_fw_version >= firmware_version("5.12.12.100") && (_device_capabilities & ds_caps::CAP_GLOBAL_SHUTTER) == ds_caps::CAP_GLOBAL_SHUTTER)
{
depth_sensor.register_option(RS2_OPTION_INTER_CAM_SYNC_MODE,
std::make_shared<external_sync_mode>(*_hw_monitor, &raw_depth_sensor, 3));
std::make_shared<external_sync_mode>(*_hw_monitor, raw_depth_sensor, 3));
}
else if (_fw_version >= firmware_version("5.12.4.0") && (_device_capabilities & ds_caps::CAP_GLOBAL_SHUTTER) == ds_caps::CAP_GLOBAL_SHUTTER)
{
depth_sensor.register_option(RS2_OPTION_INTER_CAM_SYNC_MODE,
std::make_shared<external_sync_mode>(*_hw_monitor, &raw_depth_sensor, 2));
std::make_shared<external_sync_mode>(*_hw_monitor, raw_depth_sensor, 2));
}
else if (_fw_version >= firmware_version("5.9.15.1"))
{
depth_sensor.register_option(RS2_OPTION_INTER_CAM_SYNC_MODE,
std::make_shared<external_sync_mode>(*_hw_monitor, &raw_depth_sensor, 1));
std::make_shared<external_sync_mode>(*_hw_monitor, raw_depth_sensor, 1));
}
}

Expand Down Expand Up @@ -1283,27 +1280,23 @@ namespace librealsense
auto pid = dev_info->get_group().uvc_devices.front().pid;
if (pid != RS_USB2_PID)
{
auto& depth_ep = get_raw_depth_sensor();
auto depth_ep = get_raw_depth_sensor();
auto emitter_enabled = std::make_shared<emitter_option>(depth_ep);
depth_ep.register_option(RS2_OPTION_EMITTER_ENABLED, emitter_enabled);
depth_ep->register_option(RS2_OPTION_EMITTER_ENABLED, emitter_enabled);

auto laser_power = std::make_shared<uvc_xu_option<uint16_t>>(depth_ep,
depth_xu,
DS5_LASER_POWER,
"Manual laser power in mw. applicable only when laser power mode is set to Manual");
depth_ep.register_option(RS2_OPTION_LASER_POWER,
std::make_shared<auto_disabling_control>(
laser_power,
emitter_enabled,
std::vector<float>{0.f, 2.f}, 1.f));

auto uvc_s = std::dynamic_pointer_cast<uvc_sensor>(depth_ep.shared_from_this());
if (!uvc_s)
throw std::runtime_error("Sensor base is not uvc sensor");

depth_ep.register_option(RS2_OPTION_PROJECTOR_TEMPERATURE,
std::make_shared<asic_and_projector_temperature_options>(std::move(uvc_s),
RS2_OPTION_PROJECTOR_TEMPERATURE));
"Manual laser power in mw. applicable only when laser power mode is set to Manual" );
depth_ep->register_option(RS2_OPTION_LASER_POWER,
std::make_shared< auto_disabling_control >( laser_power,
emitter_enabled,
std::vector< float >{ 0.f, 2.f },
1.f ) );

depth_ep->register_option(RS2_OPTION_PROJECTOR_TEMPERATURE,
std::make_shared< asic_and_projector_temperature_options >( depth_ep,
RS2_OPTION_PROJECTOR_TEMPERATURE ) );
}
}
}
4 changes: 2 additions & 2 deletions src/ds/d400/d400-device.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,10 +39,10 @@ namespace librealsense
return dynamic_cast<synthetic_sensor&>(get_sensor(_depth_device_idx));
}

uvc_sensor& get_raw_depth_sensor()
std::shared_ptr< uvc_sensor > get_raw_depth_sensor()
{
synthetic_sensor& depth_sensor = get_depth_sensor();
return dynamic_cast<uvc_sensor&>(*depth_sensor.get_raw_sensor());
return std::dynamic_pointer_cast< uvc_sensor >( depth_sensor.get_raw_sensor() );
}

d400_device( std::shared_ptr< const d400_info > const & );
Expand Down
7 changes: 3 additions & 4 deletions src/ds/d500/d500-color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -94,10 +94,9 @@ namespace librealsense
void d500_color::init()
{
auto& color_ep = get_color_sensor();
auto& raw_color_ep = get_raw_color_sensor();
auto raw_color_ep = get_raw_color_sensor();

_ds_color_common = std::make_shared<ds_color_common>(raw_color_ep, color_ep,
_fw_version, _hw_monitor, this);
_ds_color_common = std::make_shared<ds_color_common>(raw_color_ep, color_ep, _fw_version, _hw_monitor, this);

register_color_features();
register_options();
Expand Down Expand Up @@ -134,7 +133,7 @@ namespace librealsense
void d500_color::register_options()
{
auto& color_ep = get_color_sensor();
auto& raw_color_ep = get_raw_color_sensor();
auto raw_color_ep = get_raw_color_sensor();

_ds_color_common->register_color_options();

Expand Down
6 changes: 3 additions & 3 deletions src/ds/d500/d500-color.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,10 @@ namespace librealsense
return dynamic_cast<synthetic_sensor&>(get_sensor(_color_device_idx));
}

uvc_sensor& get_raw_color_sensor()
std::shared_ptr< uvc_sensor > get_raw_color_sensor()
{
synthetic_sensor& color_sensor = get_color_sensor();
return dynamic_cast<uvc_sensor&>(*color_sensor.get_raw_sensor());
synthetic_sensor & color_sensor = get_color_sensor();
return std::dynamic_pointer_cast< uvc_sensor >( color_sensor.get_raw_sensor() );
}

protected:
Expand Down
Loading

0 comments on commit 77d1e1c

Please sign in to comment.