98 size_t dataLength)
const
106 cmd.require_response =
false;
139 <<
"Min and Max firmware versions have not been defined for this device: "
140 << std::hex <<
_pid );
192 auto uvc = As< librealsense::uvc_sensor >(
s);
194 uvc->set_frame_metadata_modifier(callback);
241 for (
auto&&
p : results)
266 std::weak_ptr<d400_depth_sensor> wp =
267 std::dynamic_pointer_cast<d400_depth_sensor>(this->shared_from_this());
268 vid_profile->set_intrinsics([
profile, wp]()
272 return sp->get_color_intrinsics(
profile);
281 std::weak_ptr<d400_depth_sensor> wp =
282 std::dynamic_pointer_cast<d400_depth_sensor>(this->shared_from_this());
283 vid_profile->set_intrinsics([
profile, wp]()
287 return sp->get_intrinsics(
profile);
334 return preset_max_value;
358 for (
auto&&
p : results)
383 std::weak_ptr<d400_depth_sensor> wp = std::dynamic_pointer_cast<d400_depth_sensor>(this->shared_from_this());
384 video->set_intrinsics([
profile, wp]()
388 return sp->get_intrinsics(
profile);
411 return fabs(
table->baseline);
437 val |= ds_caps::CAP_ACTIVE_PROJECTOR;
439 val |= ds_caps::CAP_RGB_SENSOR;
442 val |= ds_caps::CAP_IMU_SENSOR;
444 val |= ds_caps::CAP_BMI_055;
446 val |= ds_caps::CAP_BMI_085;
448 val |= ds_caps::CAP_BMI_055;
450 val |= ds_caps::CAP_BMI_085;
455 val |= ds_caps::CAP_FISHEYE_SENSOR;
457 val |= ds_caps::CAP_ROLLING_SHUTTER;
459 val |= ds_caps::CAP_GLOBAL_SHUTTER;
462 val |= ds_caps::CAP_INTERCAM_HW_SYNC;
464 val |= ds_caps::CAP_IP65;
466 val |= ds_caps::CAP_IR_FILTER;
471 const std::vector<platform::uvc_device_info>& all_device_infos)
475 std::vector<std::shared_ptr<platform::uvc_device>> depth_devices;
479 std::unique_ptr< frame_timestamp_reader > timestamp_reader_backup(
new ds_timestamp_reader() );
481 if (all_device_infos.front().pid !=
RS457_PID)
486 std::unique_ptr<frame_timestamp_reader> timestamp_reader_metadata(timestamp_reader_from_metadata);
487 auto enable_global_time_option = std::shared_ptr<global_time_option>(
new global_time_option());
489 auto raw_depth_ep = std::make_shared<uvc_sensor>(
"Raw Depth Sensor", std::make_shared<platform::multi_pins_uvc_device>(depth_devices),
492 raw_depth_ep->register_xu(
depth_xu);
494 auto depth_ep = std::make_shared<d400_depth_sensor>(
this, raw_depth_ep);
519 init( dev_info->get_context(), dev_info->get_group() );
540 std::make_shared<locked_transfer>(
548 std::make_shared< locked_transfer >(
584 using namespace platform;
589 std::string optic_serial, asic_serial, pid_hex_str, usb_type_str;
590 bool advanced_mode, usb_modality;
611 _usb_mode = raw_depth_sensor->get_usb_specification();
615 usb_modality =
false;
626 []() {
return std::make_shared<y8i_to_y8y8>(); }
634 []() {
return std::make_shared<y12i_to_y16y16>(); }
642 []() {
return std::make_shared<y12i_to_y16y16_mipi>(); }
653 "Hardware pipe configuration" ) );
656 "Set the power level of the LED, with 0 meaning LED off"));
671 std::make_shared<asic_temperature_option_mipi>(
_hw_monitor,
678 "Generate trigger from the camera to external device once per frame"));
681 std::make_shared< asic_and_projector_temperature_options >( raw_depth_sensor,
685 auto error_control = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor,
depth_xu,
690 raw_depth_sensor->get_notifications_processor(),
699 auto thermal_compensation_toggle = std::make_shared<protected_xu_option<uint8_t>>( raw_depth_sensor,
depth_xu,
704 _thermal_monitor = std::make_shared<d400_thermal_monitor>(temperature_sensor, thermal_compensation_toggle);
707 std::make_shared<thermal_compensation>(
_thermal_monitor,thermal_compensation_toggle));
710 auto ir_filter_mask = ds_caps::CAP_IR_FILTER;
718 auto ip65_mask = ds_caps::CAP_IP65;
726 std::shared_ptr<option> exposure_option =
nullptr;
727 std::shared_ptr<option> gain_option =
nullptr;
728 std::shared_ptr<hdr_option> hdr_enabled_option =
nullptr;
731 auto uvc_xu_exposure_option = std::make_shared<uvc_xu_option<uint32_t>>( raw_depth_sensor,
734 "Depth Exposure (usec)");
736 auto uvc_pu_gain_option = std::make_shared<uvc_pu_option>( raw_depth_sensor,
RS2_OPTION_GAIN);
740 auto enable_auto_exposure = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor,
743 "Enable Auto Exposure");
749 auto d400_depth = As<d400_depth_sensor, synthetic_sensor>(&
get_depth_sensor());
751 auto&& hdr_cfg = d400_depth->get_hdr_config();
757 std::map<float, std::string>{ {0.f,
"0"}, { 1.f,
"1" }, { 2.f,
"2" }, { 3.f,
"3" } });
760 option_range hdr_sequence_size_range = { 2.f , 2.f , 1.f , 2.f };
761 auto hdr_sequence_size_option = std::make_shared<hdr_option>(hdr_cfg,
RS2_OPTION_SEQUENCE_SIZE, hdr_sequence_size_range,
762 std::map<float, std::string>{ { 2.f,
"2" } });
765 option_range hdr_sequ_id_range = { 0.f , 2.f , 1.f , 0.f };
766 auto hdr_sequ_id_option = std::make_shared<hdr_option>(hdr_cfg,
RS2_OPTION_SEQUENCE_ID, hdr_sequ_id_range,
767 std::map<float, std::string>{ {0.f,
"UVC"}, { 1.f,
"1" }, { 2.f,
"2" } });
770 option_range hdr_enable_range = { 0.f , 1.f , 1.f , 0.f };
779 auto hdr_conditional_exposure_option = std::make_shared<hdr_conditional_option>(hdr_cfg, uvc_xu_exposure_option, hdr_exposure_option);
780 auto hdr_conditional_gain_option = std::make_shared<hdr_conditional_option>(hdr_cfg, uvc_pu_gain_option, hdr_gain_option);
782 exposure_option = hdr_conditional_exposure_option;
783 gain_option = hdr_conditional_gain_option;
785 std::vector<std::pair<std::shared_ptr<option>,
std::string>> options_and_reasons = { std::make_pair(hdr_enabled_option,
786 "Auto Exposure cannot be set while HDR is enabled") };
788 std::make_shared<gated_option>(
789 enable_auto_exposure,
790 options_and_reasons));
794 exposure_option = uvc_xu_exposure_option;
795 gain_option = uvc_pu_gain_option;
801 auto depth_auto_exposure_mode = std::make_shared<uvc_xu_option<uint8_t>>( raw_depth_sensor,
804 "Depth Auto Exposure Mode",
805 std::map<float, std::string>{
815 std::make_shared<auto_disabling_control>(
817 enable_auto_exposure));
821 std::make_shared<auto_disabling_control>(
823 enable_auto_exposure));
826 auto mask = ds_caps::CAP_GLOBAL_SHUTTER | ds_caps::CAP_ACTIVE_PROJECTOR;
831 auto alternating_emitter_opt = std::make_shared<alternating_emitter_option>(*
_hw_monitor, is_fw_version_using_id);
836 std::vector<std::pair<std::shared_ptr<option>,
std::string>> options_and_reasons = { std::make_pair(alternating_emitter_opt,
837 "Emitter always ON cannot be set while Emitter ON/OFF is enabled") };
839 std::make_shared<gated_option>(
840 emitter_always_on_opt,
841 options_and_reasons));
846 std::vector<std::pair<std::shared_ptr<option>,
std::string>> options_and_reasons = { std::make_pair(hdr_enabled_option,
"Emitter ON/OFF cannot be set while HDR is enabled"),
847 std::make_pair(emitter_always_on_opt,
"Emitter ON/OFF cannot be set while Emitter always ON is enabled") };
849 std::make_shared<gated_option>(
850 alternating_emitter_opt,
856 std::vector<std::pair<std::shared_ptr<option>,
std::string>> options_and_reasons = { std::make_pair(emitter_always_on_opt,
857 "Emitter ON/OFF cannot be set while Emitter always ON is enabled") };
859 std::make_shared<gated_option>(
860 alternating_emitter_opt,
861 options_and_reasons));
875 std::make_shared<external_sync_mode>(*
_hw_monitor, raw_depth_sensor, 3));
880 std::make_shared<external_sync_mode>(*
_hw_monitor, raw_depth_sensor, 2));
885 std::make_shared<external_sync_mode>(*
_hw_monitor, raw_depth_sensor, 1));
892 std::make_shared< const_value_option >(
893 "Distance in mm between the stereo imagers",
912 float default_depth_units = 0.001f;
915 default_depth_units = 0.0001f;
1223 throw std::runtime_error(
"Not enough bytes returned from the firmware!");
1241 const std::vector<platform::uvc_device_info>& all_device_infos)
1245 std::vector<std::shared_ptr<platform::uvc_device>> depth_devices;
1249 std::unique_ptr< frame_timestamp_reader > d400_timestamp_reader_backup(
new ds_timestamp_reader() );
1252 auto enable_global_time_option = std::shared_ptr<global_time_option>(
new global_time_option());
1253 auto raw_depth_ep = std::make_shared<uvc_sensor>(
ds::DEPTH_STEREO, std::make_shared<platform::multi_pins_uvc_device>(depth_devices), std::unique_ptr<frame_timestamp_reader>(
new global_timestamp_reader(std::move(d400_timestamp_reader_metadata),
_tf_keeper, enable_global_time_option)),
this);
1254 auto depth_ep = std::make_shared<ds5u_depth_sensor>(
this, raw_depth_ep);
1258 raw_depth_ep->register_xu(
depth_xu);
1277 init( dev_info->get_context(), dev_info->get_group() );
1288 auto pid = dev_info->get_group().uvc_devices.front().pid;
1292 auto emitter_enabled = std::make_shared<emitter_option>(depth_ep);
1295 auto laser_power = std::make_shared<uvc_xu_option<uint16_t>>(depth_ep,
1298 "Manual laser power in mw. applicable only when laser power mode is set to Manual" );
1300 std::make_shared< auto_disabling_control >( laser_power,
1302 std::vector< float >{ 0.f, 2.f },
1306 std::make_shared< asic_and_projector_temperature_options >( depth_ep,