Skip to content
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion src/l500/l500-options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -247,7 +247,7 @@ namespace librealsense
= static_cast< float >( usb3mode ? RS2_SENSOR_MODE_VGA : RS2_SENSOR_MODE_QVGA );

auto resolution_option = std::make_shared< sensor_mode_option >(
this,
this, &depth_sensor,
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You can use _l500_depth_dev->get_depth_sensor();

option_range{ RS2_SENSOR_MODE_VGA,
RS2_SENSOR_MODE_COUNT - 1,
1,
Expand Down Expand Up @@ -791,6 +791,9 @@ namespace librealsense

void sensor_mode_option::set(float value)
{
if (is_read_only())
throw std::runtime_error("Cannot change sensor mode while streaming!");

if (_value == value) return;

// Restrictions for sensor mode option as required on [RS5-8358]
Expand Down
7 changes: 6 additions & 1 deletion src/l500/l500-options.h
Original file line number Diff line number Diff line change
Expand Up @@ -130,11 +130,16 @@ namespace librealsense
, public observable_option
{
public:
sensor_mode_option(l500_device *l500_depth_dev, option_range range, std::string description) : float_option_with_description<rs2_sensor_mode>(range, description), _l500_depth_dev(l500_depth_dev) {};
sensor_mode_option(l500_device *l500_depth_dev, sensor_base* depth_ep, option_range range, std::string description) : float_option_with_description<rs2_sensor_mode>(range, description), _l500_depth_dev(l500_depth_dev),_sensor(depth_ep) {};
void set(float value) override;
bool is_read_only() const override
{
return _sensor && _sensor->is_opened();
}

private:
l500_device *_l500_depth_dev;
sensor_base* _sensor;
};

class ir_reflectivity_option : public bool_option
Expand Down
8 changes: 6 additions & 2 deletions unit-tests/live/presets/presets-common.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,9 @@ inline void reset_camera_preset_mode_to_defaults( const rs2::sensor & sens )
{
REQUIRE_NOTHROW(
sens.set_option(RS2_OPTION_VISUAL_PRESET, sens.get_option_range(RS2_OPTION_VISUAL_PRESET).def));
REQUIRE_NOTHROW(sens.set_option(RS2_OPTION_SENSOR_MODE, sens.get_option_range(RS2_OPTION_SENSOR_MODE).def));
if (!sens.is_option_read_only(RS2_OPTION_SENSOR_MODE)) {
REQUIRE_NOTHROW(sens.set_option(RS2_OPTION_SENSOR_MODE, sens.get_option_range(RS2_OPTION_SENSOR_MODE).def));
}
}

inline preset_mode_pair get_camera_preset_mode_defaults(const rs2::sensor & sens)
Expand Down Expand Up @@ -422,7 +424,9 @@ void stop_depth( const rs2::sensor & sens )

void set_mode_preset( const rs2::sensor & sens, preset_mode_pair preset_mode)
{
REQUIRE_NOTHROW( sens.set_option( RS2_OPTION_SENSOR_MODE, (float)preset_mode.second) );
if (!sens.is_option_read_only(RS2_OPTION_SENSOR_MODE)) {
REQUIRE_NOTHROW(sens.set_option(RS2_OPTION_SENSOR_MODE, (float)preset_mode.second));
}
REQUIRE_NOTHROW( sens.set_option( RS2_OPTION_VISUAL_PRESET, (float)preset_mode.first) );
CHECK( sens.get_option( RS2_OPTION_VISUAL_PRESET ) == (float)preset_mode.first);
}
Expand Down