Skip to content

Commit

Permalink
PR IntelRealSense#12624 from SamerKhshiboun: Remove SKU D465
Browse files Browse the repository at this point in the history
  • Loading branch information
SamerKhshiboun authored Feb 7, 2024
2 parents 6926aff + b625a20 commit d06f21b
Show file tree
Hide file tree
Showing 9 changed files with 10 additions and 100 deletions.
4 changes: 1 addition & 3 deletions src/ds/advanced_mode/advanced_mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ namespace librealsense
return results[4] > 0;
};

// "Remove IR Pattern" visual preset is available only for D400, D410, D415, D460, D465
// "Remove IR Pattern" visual preset is available only for D400, D410, D415, D460
if (is_enabled())
register_to_visual_preset_option();

Expand Down Expand Up @@ -111,7 +111,6 @@ namespace librealsense
case ds::RS430_PID:
case ds::RS430I_PID:
case ds::RS435_RGB_PID:
case ds::RS465_PID:
case ds::RS435I_PID:
default_430(p);
break;
Expand Down Expand Up @@ -179,7 +178,6 @@ namespace librealsense
case ds::RS400_PID:
case ds::RS410_PID:
case ds::RS415_PID:
case ds::RS465_PID://TODO: verify
d415_remove_ir(p);
break;
case ds::RS460_PID:
Expand Down
20 changes: 3 additions & 17 deletions src/ds/d400/d400-color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,15 +164,7 @@ namespace librealsense
// Currently disabled for certain sensors
if (!val_in_range(_pid, { ds::RS457_PID}))
{
if (!val_in_range(_pid, { ds::RS465_PID }))
{
color_ep.register_pu(RS2_OPTION_AUTO_EXPOSURE_PRIORITY);
}
// From 5.11.15 auto-exposure priority is supported on the D465
else if (_fw_version >= firmware_version("5.11.15.0"))
{
color_ep.register_pu(RS2_OPTION_AUTO_EXPOSURE_PRIORITY);
}
color_ep.register_pu(RS2_OPTION_AUTO_EXPOSURE_PRIORITY);
}

_ds_color_common->register_standard_options();
Expand All @@ -187,7 +179,7 @@ namespace librealsense
}

// Currently disabled for certain sensors
if (!val_in_range(_pid, { ds::RS465_PID, ds::RS457_PID}))
if (!val_in_range(_pid, { ds::RS457_PID }))
{
color_ep.register_pu(RS2_OPTION_HUE);
}
Expand Down Expand Up @@ -241,13 +233,7 @@ namespace librealsense
{
color_ep.register_processing_block(processing_block_factory::create_pbf_vector<yuy2_converter>(RS2_FORMAT_YUYV, map_supported_color_formats(RS2_FORMAT_YUYV), RS2_STREAM_COLOR));
}
}

if (_pid == ds::RS465_PID)
{
color_ep.register_processing_block({ {RS2_FORMAT_MJPEG} }, { {RS2_FORMAT_RGB8, RS2_STREAM_COLOR} }, []() { return std::make_shared<mjpeg_converter>(RS2_FORMAT_RGB8); });
color_ep.register_processing_block(processing_block_factory::create_id_pbf(RS2_FORMAT_MJPEG, RS2_STREAM_COLOR));
}
}
}

void d400_color::register_metadata_mipi(const synthetic_sensor &color_ep) const
Expand Down
1 change: 0 additions & 1 deletion src/ds/d400/d400-device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,6 @@ namespace librealsense
case ds::RS400_PID:
case ds::RS410_PID:
case ds::RS415_PID:
case ds::RS465_PID:
case ds::RS460_PID:
preset_max_value = static_cast<float>(RS2_RS400_VISUAL_PRESET_REMOVE_IR_PATTERN);
break;
Expand Down
56 changes: 0 additions & 56 deletions src/ds/d400/d400-factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -877,50 +877,6 @@ namespace librealsense
}
};

class rs465_device : public d400_active,
public d400_nonmonochrome,
public d400_color,
public d400_motion,
public ds_advanced_mode_base,
public firmware_logger_device
{
public:
rs465_device( std::shared_ptr< const d400_info > const & dev_info, bool register_device_notifications )
: device( dev_info, register_device_notifications )
, backend_device( dev_info, register_device_notifications )
, d400_device( dev_info )
, d400_active( dev_info )
, d400_color( dev_info )
, d400_motion( dev_info )
, d400_nonmonochrome( dev_info )
, ds_advanced_mode_base( d400_device::_hw_monitor, get_depth_sensor() )
, firmware_logger_device(
dev_info, d400_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command() )
{
}

std::shared_ptr<matcher> create_matcher(const frame_holder& frame) const override;

std::vector<tagged_profile> get_profiles_tags() const override
{
std::vector<tagged_profile> tags;
auto usb_spec = get_usb_spec();
bool usb3mode = (usb_spec >= platform::usb3_type || usb_spec == platform::usb_undefined);

int width = usb3mode ? 1280 : 640;
int height = usb3mode ? 720 : 480;
int fps = usb3mode ? 30 : 15;

tags.push_back({ RS2_STREAM_COLOR, -1, width, height, RS2_FORMAT_RGB8, fps, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT });
tags.push_back({ RS2_STREAM_DEPTH, -1, width, height, RS2_FORMAT_Z16, fps, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT });
tags.push_back({ RS2_STREAM_INFRARED, -1, width, height, RS2_FORMAT_Y8, fps, profile_tag::PROFILE_TAG_SUPERSET });
tags.push_back({ RS2_STREAM_GYRO, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, (int)odr::IMU_FPS_200, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT });
tags.push_back({ RS2_STREAM_ACCEL, -1, 0, 0, RS2_FORMAT_MOTION_XYZ32F, (int)odr::IMU_FPS_100, profile_tag::PROFILE_TAG_SUPERSET | profile_tag::PROFILE_TAG_DEFAULT });

return tags;
};
};

class rs400_imu_device : public d400_motion,
public ds_advanced_mode_base,
public firmware_logger_device
Expand Down Expand Up @@ -1137,8 +1093,6 @@ namespace librealsense
return std::make_shared< rs435_device >( dev_info, register_device_notifications );
case RS435I_PID:
return std::make_shared< rs435i_device >( dev_info, register_device_notifications );
case RS465_PID:
return std::make_shared< rs465_device >( dev_info, register_device_notifications );
case RS_USB2_PID:
return std::make_shared< rs410_device >( dev_info, register_device_notifications );
case RS400_IMU_PID:
Expand Down Expand Up @@ -1259,16 +1213,6 @@ namespace librealsense
return matcher_factory::create(RS2_MATCHER_DEFAULT, streams);
}

std::shared_ptr<matcher> rs465_device::create_matcher(const frame_holder& frame) const
{
std::vector<stream_interface*> streams = { _depth_stream.get() , _left_ir_stream.get() , _right_ir_stream.get(), _color_stream.get() };
// TODO - A proper matcher for High-FPS sensor is required
std::vector<stream_interface*> mm_streams = { _ds_motion_common->get_accel_stream().get(),
_ds_motion_common->get_gyro_stream().get()};
streams.insert(streams.end(), mm_streams.begin(), mm_streams.end());
return matcher_factory::create(RS2_MATCHER_DEFAULT, streams);
}

std::shared_ptr<matcher> rs416_device::create_matcher(const frame_holder& frame) const
{
std::vector<stream_interface*> streams = { _depth_stream.get() , _left_ir_stream.get() , _right_ir_stream.get() };
Expand Down
10 changes: 5 additions & 5 deletions src/ds/d400/d400-nonmonochrome.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,13 @@ namespace librealsense
auto pid = dev_info->get_group().uvc_devices.front().pid;
auto& depth_ep = get_depth_sensor();

// RGB for D455/D465 from Left Imager is available with FW 5.12.8.100
if ((val_in_range(pid, { RS455_PID , RS465_PID })) && (_fw_version < firmware_version("5.12.8.100")))
// RGB for D455 from Left Imager is available with FW 5.12.8.100
if ((val_in_range(pid, { RS455_PID })) && (_fw_version < firmware_version("5.12.8.100")))
return;

if ((_fw_version >= firmware_version("5.5.8.0")) && (!val_in_range(pid, { RS_USB2_PID, RS465_PID })))
if ((_fw_version >= firmware_version("5.5.8.0")) && (!val_in_range(pid, { RS_USB2_PID })))
{
if (!val_in_range(pid, { RS405_PID , RS455_PID, RS465_PID }))
if (!val_in_range(pid, { RS405_PID, RS455_PID }))
{
depth_ep.register_option(RS2_OPTION_ENABLE_AUTO_WHITE_BALANCE,
std::make_shared<uvc_xu_option<uint8_t>>(get_raw_depth_sensor(),
Expand All @@ -53,7 +53,7 @@ namespace librealsense

depth_ep.register_processing_block(processing_block_factory::create_pbf_vector<uyvy_converter>(RS2_FORMAT_UYVY, map_supported_color_formats(RS2_FORMAT_UYVY), RS2_STREAM_INFRARED));

if (!val_in_range(pid, { RS405_PID , RS455_PID, RS465_PID }))
if (!val_in_range(pid, { RS405_PID , RS455_PID }))
get_depth_sensor().unregister_option(RS2_OPTION_EMITTER_ON_OFF);

if ((_fw_version >= firmware_version("5.9.13.6") &&
Expand Down
1 change: 0 additions & 1 deletion src/ds/d400/d400-private.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ namespace librealsense
case RS415_PID:
case RS416_RGB_PID:
case RS435_RGB_PID:
case RS465_PID:
found = (result.mi == 5);
break;
default:
Expand Down
10 changes: 1 addition & 9 deletions src/ds/d400/d400-private.h
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ namespace librealsense
const uint16_t RS435I_PID = 0x0b3a; // D435i
const uint16_t RS416_PID = 0x0b49; // F416
const uint16_t RS430I_PID = 0x0b4b; // D430i
const uint16_t RS465_PID = 0x0b4d; // D465
const uint16_t RS416_RGB_PID = 0x0B52; // F416 RGB
const uint16_t RS405_PID = 0x0B5B; // D405
const uint16_t RS455_PID = 0x0B5C; // D455
Expand All @@ -59,7 +58,6 @@ namespace librealsense
ds::RS435I_PID,
ds::RS416_RGB_PID,
ds::RS430I_PID,
ds::RS465_PID,
ds::RS416_PID,
ds::RS405_PID,
ds::RS455_PID,
Expand All @@ -75,15 +73,13 @@ namespace librealsense
ds::RS430_MM_RGB_PID,
ds::RS435_RGB_PID,
ds::RS435I_PID,
ds::RS465_PID,
ds::RS455_PID,
ds::RS457_PID
};

static const std::set<std::uint16_t> d400_hid_sensors_pid = {
ds::RS435I_PID,
ds::RS430I_PID,
ds::RS465_PID,
ds::RS455_PID
};

Expand All @@ -93,9 +89,7 @@ namespace librealsense
ds::RS455_PID
};

static const std::set<std::uint16_t> d400_hid_bmi_085_pid = {
RS465_PID
};
static const std::set<std::uint16_t> d400_hid_bmi_085_pid = { };

static const std::set<std::uint16_t> d400_fisheye_pid = {
ds::RS400_MM_PID,
Expand Down Expand Up @@ -126,7 +120,6 @@ namespace librealsense
{ RS435I_PID, "Intel RealSense D435I" },
{ RS416_PID, "Intel RealSense F416"},
{ RS430I_PID, "Intel RealSense D430I"},
{ RS465_PID, "Intel RealSense D465" },
{ RS416_RGB_PID, "Intel RealSense F416 with RGB Module"},
{ RS405_PID, "Intel RealSense D405" },
{ RS455_PID, "Intel RealSense D455" },
Expand Down Expand Up @@ -154,7 +147,6 @@ namespace librealsense
{RS435I_PID, "5.12.7.100" },
{RS416_PID, "5.8.15.0" },
{RS430I_PID, "5.8.15.0" },
{RS465_PID, "5.12.7.100" },
{RS416_RGB_PID, "5.8.15.0" },
{RS405_PID, "5.12.11.8" },
{RS455_PID, "5.13.0.50" },
Expand Down
7 changes: 0 additions & 7 deletions src/ds/ds-calib-parsers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -164,13 +164,6 @@ namespace librealsense
_def_extr = { { 1, 0, 0, 0, 1, 0, 0, 0, 1 },{ -0.03022f, 0.0074f, 0.01602f } };
_imu_2_depth_rot = { { -1,0,0 },{ 0,1,0 },{ 0,0,-1 } };
}
else if (_pid == ds::RS465_PID)
{
// D465 specific - Bosch BMI085
// TODO - verify with mechanical drawing
_def_extr = { { 1, 0, 0, 0, 1, 0, 0, 0, 1 },{ -0.10125f, -0.00375f, -0.0013f } };
_imu_2_depth_rot = { { 1,0,0 },{ 0,1,0 },{ 0,0,1 } };
}
else // unmapped configurations
{
// IMU on new devices is oriented such that FW output is consistent with D435i
Expand Down
1 change: 0 additions & 1 deletion unit-tests/live/dfu/test-device-fw-compatibility.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
'0B3A': d400_fw_min_version_2, # D435I
'0B49': d400_fw_min_version_1, # D416
'0B4B': d400_fw_min_version_1, # D430I
'0B4D': d400_fw_min_version_2, # D465
'0B52': d400_fw_min_version_1, # D416_RGB
'0B5B': d400_fw_min_version_3, # D405
'0B5C': d400_fw_min_version_4 # D455
Expand Down

0 comments on commit d06f21b

Please sign in to comment.