Skip to content

Commit

Permalink
Merge pull request #9692 from nohayassin/dso_17393_fix
Browse files Browse the repository at this point in the history
Reset Auto Exp/Gain Limit back to default value 0
  • Loading branch information
ev-mp authored Oct 12, 2021
2 parents 68dd867 + 0a4b922 commit dd48c6d
Show file tree
Hide file tree
Showing 9 changed files with 253 additions and 12 deletions.
2 changes: 2 additions & 0 deletions include/librealsense2/h/rs_option.h
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,8 @@ extern "C" {
RS2_OPTION_TRANSMITTER_FREQUENCY, /**<changes the transmitter frequencies increasing effective range over sharpness. */
RS2_OPTION_VERTICAL_BINNING, /**< Enables vertical binning which increases the maximal sensed distance. */
RS2_OPTION_RECEIVER_SENSITIVITY, /**< Control receiver sensitivity to incoming light, both projected and ambient (same as APD on L515). */
RS2_OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE, /**< Enable / disable color image auto-exposure*/
RS2_OPTION_AUTO_GAIN_LIMIT_TOGGLE, /**< Enable / disable color image auto-gain*/
RS2_OPTION_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
} rs2_option;

Expand Down
28 changes: 26 additions & 2 deletions src/ds5/ds5-device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1081,8 +1081,32 @@ namespace librealsense
{
auto exposure_range = depth_sensor.get_option(RS2_OPTION_EXPOSURE).get_range();
auto gain_range = depth_sensor.get_option(RS2_OPTION_GAIN).get_range();
depth_sensor.register_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT, std::make_shared<auto_exposure_limit_option>(*_hw_monitor, &depth_sensor, exposure_range));
depth_sensor.register_option(RS2_OPTION_AUTO_GAIN_LIMIT, std::make_shared<auto_gain_limit_option>(*_hw_monitor, &depth_sensor, gain_range));

option_range enable_range = { 0.f /*min*/, 1.f /*max*/, 1.f /*step*/, 0.f /*default*/ };

//GAIN Limit
auto gain_limit_toggle_control = std::make_shared<limits_option>(RS2_OPTION_AUTO_GAIN_LIMIT_TOGGLE, enable_range, "Toggle Auto-Gain Limit", *_hw_monitor);
_gain_limit_value_control = std::make_shared<auto_gain_limit_option>(*_hw_monitor, &depth_sensor, gain_range, gain_limit_toggle_control);
depth_sensor.register_option(RS2_OPTION_AUTO_GAIN_LIMIT_TOGGLE, gain_limit_toggle_control);

depth_sensor.register_option(RS2_OPTION_AUTO_GAIN_LIMIT,
std::make_shared<auto_disabling_control>(
_gain_limit_value_control,
gain_limit_toggle_control

));

// EXPOSURE Limit
auto ae_limit_toggle_control = std::make_shared<limits_option>(RS2_OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE, enable_range, "Toggle Auto-Exposure Limit", *_hw_monitor);
_ae_limit_value_control = std::make_shared<auto_exposure_limit_option>(*_hw_monitor, &depth_sensor, exposure_range, ae_limit_toggle_control);
depth_sensor.register_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE, ae_limit_toggle_control);

depth_sensor.register_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT,
std::make_shared<auto_disabling_control>(
_ae_limit_value_control,
ae_limit_toggle_control

));
}

// attributes of md_capture_timing
Expand Down
4 changes: 4 additions & 0 deletions src/ds5/ds5-device.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
#include "global_timestamp_reader.h"
#include "fw-update/fw-update-device-interface.h"
#include "ds5-auto-calibration.h"
#include "ds5-options.h"

namespace librealsense
{
Expand Down Expand Up @@ -107,6 +108,9 @@ namespace librealsense
lazy<std::vector<uint8_t>> _color_calib_table_raw;
std::shared_ptr<lazy<rs2_extrinsics>> _color_extrinsic;
bool _is_locked = true;

std::shared_ptr<auto_gain_limit_option> _gain_limit_value_control;
std::shared_ptr<auto_exposure_limit_option> _ae_limit_value_control;
};

class ds5u_device : public ds5_device
Expand Down
43 changes: 37 additions & 6 deletions src/ds5/ds5-options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -655,20 +655,29 @@ namespace librealsense
return _uvc_option->is_enabled();
}

auto_exposure_limit_option::auto_exposure_limit_option(hw_monitor& hwm, sensor_base* ep, option_range range)
: option_base(range), _hwm(hwm), _sensor(ep)
auto_exposure_limit_option::auto_exposure_limit_option(hw_monitor& hwm, sensor_base* ep, option_range range, std::shared_ptr<limits_option> exposure_limit_enable)
: option_base(range), _hwm(hwm), _sensor(ep), _exposure_limit_toggle(exposure_limit_enable)
{
_range = [range]()
{
return range;
};
if (auto toggle = _exposure_limit_toggle.lock())
toggle->set_cached_limit(range.max);
}

void auto_exposure_limit_option::set(float value)
{
if (!is_valid(value))
throw invalid_value_exception("set(enable_auto_exposure) failed! Invalid Auto-Exposure mode request " + std::to_string(value));

if (auto toggle = _exposure_limit_toggle.lock())
{
toggle->set_cached_limit(value);
if (toggle->query() == 0.f)
toggle->set(1);
}

command cmd_get(ds::AUTO_CALIB);
cmd_get.param1 = 5;
std::vector<uint8_t> ret = _hwm.send(cmd_get);
Expand All @@ -692,28 +701,44 @@ namespace librealsense
if (res.empty())
throw invalid_value_exception("auto_exposure_limit_option::query result is empty!");

return static_cast<float>(*(reinterpret_cast<uint32_t*>(res.data())));
auto ret = static_cast<float>(*(reinterpret_cast<uint32_t*>(res.data())));
if (ret< get_range().min || ret > get_range().max)
{
if (auto toggle = _exposure_limit_toggle.lock())
return toggle->get_cached_limit();
}
return ret;
}

option_range auto_exposure_limit_option::get_range() const
{
return *_range;
}

auto_gain_limit_option::auto_gain_limit_option(hw_monitor& hwm, sensor_base* ep, option_range range)
: option_base(range), _hwm(hwm), _sensor(ep)
auto_gain_limit_option::auto_gain_limit_option(hw_monitor& hwm, sensor_base* ep, option_range range, std::shared_ptr <limits_option> gain_limit_enable)
: option_base(range), _hwm(hwm), _sensor(ep), _gain_limit_toggle(gain_limit_enable)
{
_range = [range]()
{
return range;
};
if (auto toggle = _gain_limit_toggle.lock())
toggle->set_cached_limit(range.max);
}

void auto_gain_limit_option::set(float value)
{
if (!is_valid(value))
throw invalid_value_exception("set(enable_auto_gain) failed! Invalid Auto-Gain mode request " + std::to_string(value));

if (auto toggle = _gain_limit_toggle.lock())
{
toggle->set_cached_limit(value);
if (toggle->query() == 0.f)
toggle->set(1);
}


command cmd_get(ds::AUTO_CALIB);
cmd_get.param1 = 5;
std::vector<uint8_t> ret = _hwm.send(cmd_get);
Expand All @@ -737,7 +762,13 @@ namespace librealsense
if (res.empty())
throw invalid_value_exception("auto_exposure_limit_option::query result is empty!");

return static_cast<float>(*(reinterpret_cast<uint32_t*>(res.data() + 4)));
auto ret = static_cast<float>(*(reinterpret_cast<uint32_t*>(res.data() + 4)));
if (ret< get_range().min || ret > get_range().max)
{
if (auto toggle = _gain_limit_toggle.lock())
return toggle->get_cached_limit();
}
return ret;
}

option_range auto_gain_limit_option::get_range() const
Expand Down
77 changes: 74 additions & 3 deletions src/ds5/ds5-options.h
Original file line number Diff line number Diff line change
Expand Up @@ -331,11 +331,11 @@ namespace librealsense
std::shared_ptr<option> _uvc_option;
std::shared_ptr<option> _hdr_option;
};

class limits_option;
class auto_exposure_limit_option : public option_base
{
public:
auto_exposure_limit_option(hw_monitor& hwm, sensor_base* depth_ep, option_range range);
auto_exposure_limit_option(hw_monitor& hwm, sensor_base* depth_ep, option_range range, std::shared_ptr<limits_option> exposure_limit_enable);
virtual ~auto_exposure_limit_option() = default;
virtual void set(float value) override;
virtual float query() const override;
Expand All @@ -353,12 +353,13 @@ namespace librealsense
lazy<option_range> _range;
hw_monitor& _hwm;
sensor_base* _sensor;
std::weak_ptr<limits_option> _exposure_limit_toggle;
};

class auto_gain_limit_option : public option_base
{
public:
auto_gain_limit_option(hw_monitor& hwm, sensor_base* depth_ep, option_range range);
auto_gain_limit_option(hw_monitor& hwm, sensor_base* depth_ep, option_range range, std::shared_ptr<limits_option> gain_limit_enable);
virtual ~auto_gain_limit_option() = default;
virtual void set(float value) override;
virtual float query() const override;
Expand All @@ -376,8 +377,78 @@ namespace librealsense
lazy<option_range> _range;
hw_monitor& _hwm;
sensor_base* _sensor;
std::weak_ptr<limits_option> _gain_limit_toggle;
};

// Auto-Limits Enable/ Disable
class limits_option : public option
{
public:

limits_option(rs2_option option, option_range range, const char* description, hw_monitor& hwm) :
_option(option), _toggle_range(range), _description(description), _hwm(hwm) {};

virtual void set(float value) override
{
auto set_limit = _cached_limit;
if (value == 0) // 0: gain auto-limit is disabled, 1 : gain auto-limit is enabled (all range 16-248 is valid)
set_limit = 0;

command cmd_get(ds::AUTO_CALIB);
cmd_get.param1 = 5;
std::vector<uint8_t> ret = _hwm.send(cmd_get);
if (ret.empty())
throw invalid_value_exception("auto_exposure_limit_option::query result is empty!");

command cmd(ds::AUTO_CALIB);
cmd.param1 = 4;
cmd.param2 = *(reinterpret_cast<uint32_t*>(ret.data()));
cmd.param3 = static_cast<int>(set_limit);
if (_option == RS2_OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE)
{
cmd.param2 = static_cast<int>(set_limit);
cmd.param3 = *(reinterpret_cast<uint32_t*>(ret.data() + 4));
}
_hwm.send(cmd);
};
virtual float query() const override
{
auto offset = 0;
if (_option == RS2_OPTION_AUTO_GAIN_LIMIT_TOGGLE)
offset = 4;
command cmd(ds::AUTO_CALIB);
cmd.param1 = 5;
auto res = _hwm.send(cmd);
if (res.empty())
throw invalid_value_exception("auto_exposure_limit_option::query result is empty!");

auto limit_val = static_cast<float>(*(reinterpret_cast<uint32_t*>(res.data() + offset)));
if (limit_val == 0)
return 0;
return 1;
};
virtual option_range get_range() const override { return _toggle_range; };
virtual bool is_enabled() const override { return true; }
virtual const char* get_description() const override { return _description; };
virtual void enable_recording(std::function<void(const option&)> record_action) override { _record_action = record_action; }
virtual const char* get_value_description(float val) const override
{
if (_description_per_value.find(val) != _description_per_value.end())
return _description_per_value.at(val).c_str();
return nullptr;
};
void set_cached_limit(float value) { _cached_limit = value; };
float get_cached_limit() { return _cached_limit; };

private:
std::function<void(const option&)> _record_action = [](const option&) {};
rs2_option _option;
option_range _toggle_range;
const std::map<float, std::string> _description_per_value;
float _cached_limit; // used to cache contol limit value when toggle is switched to off
const char* _description;
hw_monitor& _hwm;
};

class ds5_thermal_monitor;
class thermal_compensation : public option
Expand Down
2 changes: 2 additions & 0 deletions src/to-string.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -370,6 +370,8 @@ const char * get_string( rs2_option value )
CASE( TRANSMITTER_FREQUENCY )
CASE( VERTICAL_BINNING )
CASE( RECEIVER_SENSITIVITY )
CASE(AUTO_EXPOSURE_LIMIT_TOGGLE)
CASE(AUTO_GAIN_LIMIT_TOGGLE)
default:
assert( ! is_valid( value ) );
return UNKNOWN_VALUE;
Expand Down
103 changes: 103 additions & 0 deletions unit-tests/live/d400/test-auto-limits.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2021 Intel Corporation. All Rights Reserved.

/////////////////////////////////////////////////////////////////////////////
// This set of tests is valid for any device that supports the HDR feature //
/////////////////////////////////////////////////////////////////////////////

//#test:device D400*

#include "../../catch.h"
#include "../../unit-tests-common.h"

using namespace rs2;

// HDR CONFIGURATION TESTS
TEST_CASE("Gain/ Exposure auto limits", "[live]")
{
rs2::context ctx;
auto list = ctx.query_devices();
REQUIRE(list.size());
auto dev1 = list.front();
auto dev2 = list.front();
std::array < device, 2> devices = { dev1, dev2 };

rs2_option limits_toggle[2] = { RS2_OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE, RS2_OPTION_AUTO_GAIN_LIMIT_TOGGLE };
rs2_option limits_value[2] = { RS2_OPTION_AUTO_EXPOSURE_LIMIT, RS2_OPTION_AUTO_GAIN_LIMIT };
std::array < std::map<rs2_option, sensor>, 2> picked_sensor;

// 1. Scenario 1:
// - Change control value few times
// - Turn toggle off
// - Turn toggle on
// - Check that control limit value is the latest value
// 2. Scenario 2:
// - Init 2 devices
// - Change control value for each device to different values
// - Toggle off each control
// - Toggle on each control
// - Check that control limit value in each device is set to the device cached value

for (auto i = 0; i < 2; i++) // 2 controls
{
for (auto j = 0; j < 2; j++) // 2 devices
{
auto sensors = devices[j].query_sensors();
for (auto& s : sensors)
{
std::string val = s.get_info(RS2_CAMERA_INFO_NAME);
if (!s.supports(limits_value[i]))
continue;
picked_sensor[j][limits_value[i]] = s.get();//std::make_shared<sensor>(s);
auto range = s.get_option_range(limits_value[i]);
// 1. Scenario 1:
// - Change control value few times
// - Turn toggle off
// - Turn toggle on
// - Check that control limit value is the latest value
float values[3] = { range.min + 5.0, range.max / 4.0, range.max - 5.0 };
for (auto& val : values)
s.set_option(limits_value[i], val);
s.set_option(limits_toggle[i], 0.0); // off
s.set_option(limits_toggle[i], 1.0); // on
auto limit = s.get_option(limits_value[i]);
REQUIRE(limit == values[2]);
}
}
}

// 2. Scenario 2:
// - Init 2 devices
// - toggle on both dev1 and dev2 and set two distinct values for the auto-exposure /gain.
// - toggle both dev1and dev2 off.
// 2.1. toggle dev1 on :
// * verify that the limit value is the value that was stored(cached) in dev1.
// * verify that for dev2 both the limitand the toggle values are similar to those of dev1
// 2.2. toggle dev2 on :
// * verify that the limit value is the value that was stored(cached) in dev2.

for (auto i = 0; i < 2; i++) // exposure or gain
{
auto s1 = picked_sensor[0][limits_value[i]];
auto s2 = picked_sensor[1][limits_value[i]];

auto range = s1.get_option_range(limits_value[i]); // should be same range from both sensors
s1.set_option(limits_value[i], range.max / 4.0);
s1.set_option(limits_toggle[i], 0.0); // off
s2.set_option(limits_value[i], range.max - 5.0);
s2.set_option(limits_toggle[i], 0.0); // off

// 2.1
s1.set_option(limits_toggle[i], 1.0); // on
auto limit1 = s1.get_option(limits_value[i]);
REQUIRE(limit1 == range.max / 4.0);
// keep toggle of dev2 off
auto limit2 = s2.get_option(limits_value[i]);
REQUIRE(limit1 == limit2);

// 2.2
s2.set_option(limits_toggle[i], 1.0); // on
limit2 = s2.get_option(limits_value[i]);
REQUIRE(limit2 == range.max - 5.0);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,9 @@ public enum Option {
AUTO_RX_SENSITIVITY(87),
OPTION_TRANSMITTER_FREQUENCY(88),
OPTION_VERTICAL_BINNING(89),
OPTION_RECEIVER_SENSITIVITY(90);
OPTION_RECEIVER_SENSITIVITY(90),
OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE(91),
OPTION_AUTO_GAIN_LIMIT_TOGGLE(92);

private final int mValue;

Expand Down
2 changes: 2 additions & 0 deletions wrappers/nodejs/src/addon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -4846,6 +4846,8 @@ void InitModule(v8::Local<v8::Object> exports) {
_FORCE_SET_ENUM(RS2_OPTION_TRANSMITTER_FREQUENCY);
_FORCE_SET_ENUM(RS2_OPTION_VERTICAL_BINNING);
_FORCE_SET_ENUM(RS2_OPTION_RECEIVER_SENSITIVITY);
_FORCE_SET_ENUM(RS2_OPTION_AUTO_EXPOSURE_LIMIT_TOGGLE);
_FORCE_SET_ENUM(RS2_OPTION_AUTO_GAIN_LIMIT_TOGGLE);
_FORCE_SET_ENUM(RS2_OPTION_COUNT);

// rs2_camera_info
Expand Down

0 comments on commit dd48c6d

Please sign in to comment.