Skip to content

Commit

Permalink
PR #8952 from Avishag: Support L535 options
Browse files Browse the repository at this point in the history
  • Loading branch information
maloel committed May 10, 2021
2 parents 9924d46 + 9c412cc commit b8ec3b5
Show file tree
Hide file tree
Showing 19 changed files with 327 additions and 14 deletions.
1 change: 1 addition & 0 deletions include/librealsense2/h/rs_option.h
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,7 @@ extern "C" {
RS2_OPTION_ENABLE_IR_REFLECTIVITY, /**< Enables data collection for calculating IR pixel reflectivity */
RS2_OPTION_AUTO_EXPOSURE_LIMIT, /**< Set and get auto exposure limit in microseconds. Default is 0 which means full exposure range. If the requested exposure limit is greater than frame time, it will be set to frame time at runtime. Setting will not take effect until next streaming session. */
RS2_OPTION_AUTO_GAIN_LIMIT, /**< Set and get auto gain limits ranging from 16 to 248. Default is 0 which means full gain. If the requested gain limit is less than 16, it will be set to 16. If the requested gain limit is greater than 248, it will be set to 248. Setting will not take effect until next streaming session. */
RS2_OPTION_AUTO_RX_SENSITIVITY,
RS2_OPTION_COUNT /**< Number of enumeration values. Not a valid input: intended to be used in for-loops. */
} rs2_option;

Expand Down
6 changes: 6 additions & 0 deletions src/l500/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,9 @@ target_sources(${LRS_TARGET}
"${CMAKE_CURRENT_LIST_DIR}/l500-fw-update-device.cpp"
"${CMAKE_CURRENT_LIST_DIR}/l500-serializable.cpp"
"${CMAKE_CURRENT_LIST_DIR}/l500-options.cpp"
"${CMAKE_CURRENT_LIST_DIR}/l535-device-options.cpp"
"${CMAKE_CURRENT_LIST_DIR}/l535-amc-option.cpp"
"${CMAKE_CURRENT_LIST_DIR}/l535-preset-option.cpp"

"${CMAKE_CURRENT_LIST_DIR}/l500-depth.h"
"${CMAKE_CURRENT_LIST_DIR}/l500-private.h"
Expand All @@ -21,5 +24,8 @@ target_sources(${LRS_TARGET}
"${CMAKE_CURRENT_LIST_DIR}/l500-fw-update-device.h"
"${CMAKE_CURRENT_LIST_DIR}/l500-serializable.h"
"${CMAKE_CURRENT_LIST_DIR}/l500-options.h"
"${CMAKE_CURRENT_LIST_DIR}/l535-device-options.h"
"${CMAKE_CURRENT_LIST_DIR}/l535-amc-option.h"
"${CMAKE_CURRENT_LIST_DIR}/l535-preset-option.h"
)

6 changes: 3 additions & 3 deletions src/l500/l500-factory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "l500-motion.h"
#include "l500-color.h"
#include "l500-serializable.h"

#include "l535-device-options.h"
#include "../firmware_logger_device.h"

namespace librealsense
Expand Down Expand Up @@ -65,7 +65,7 @@ namespace librealsense
};

class l535_device : public l500_depth,
public l500_options,
public l535::device_options,
public l500_color,
public l500_motion,
public l500_serializable,
Expand All @@ -78,7 +78,7 @@ namespace librealsense
: device(ctx, group, register_device_notifications),
l500_device(ctx, group),
l500_depth(ctx, group),
l500_options(ctx, group),
device_options(ctx, group),
l500_color(ctx, group),
l500_motion(ctx, group),
l500_serializable(l500_device::_hw_monitor, get_depth_sensor()),
Expand Down
6 changes: 3 additions & 3 deletions src/l500/l500-options.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,10 @@ namespace librealsense

class l500_options;

typedef uvc_xu_option< int > super;

class digital_gain_option : public super
class digital_gain_option : public uvc_xu_option< int >
{
typedef uvc_xu_option< int > super;

public:
digital_gain_option( uvc_sensor & ep,
platform::extension_unit xu,
Expand Down
13 changes: 8 additions & 5 deletions src/l500/l500-serializable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,12 +47,15 @@ namespace librealsense
RS2_OPTION_RESET_CAMERA_ACCURACY_HEALTH };

// We have to set the sensor mode (resolution) first
auto & sensor_mode = _depth_sensor.get_option( RS2_OPTION_SENSOR_MODE );
auto found_sensor_mode = j.find( get_string( RS2_OPTION_SENSOR_MODE ) );
if( found_sensor_mode != j.end() )
if (_depth_sensor.supports_option(RS2_OPTION_SENSOR_MODE))
{
float sensor_mode_val = found_sensor_mode.value();
sensor_mode.set( sensor_mode_val );
auto & sensor_mode = _depth_sensor.get_option(RS2_OPTION_SENSOR_MODE);
auto found_sensor_mode = j.find(get_string(RS2_OPTION_SENSOR_MODE));
if (found_sensor_mode != j.end())
{
float sensor_mode_val = found_sensor_mode.value();
sensor_mode.set(sensor_mode_val);
}
}

// If a non custom preset is used, we should ignore all the settings that are
Expand Down
81 changes: 81 additions & 0 deletions src/l500/l535-amc-option.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
//// License: Apache 2.0. See LICENSE file in root directory.
//// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#include "l535-amc-option.h"
#include "l500-private.h"
#include "l500-depth.h"


using librealsense::ivcam2::l535::amc_option;

amc_option::amc_option( librealsense::l500_device * l500_dev,
librealsense::hw_monitor * hw_monitor,
librealsense::ivcam2::l535::amc_control type,
const std::string & description )
: _device( l500_dev )
, _hw_monitor( hw_monitor )
, _control( type )
, _description( description )
{
// Keep the USB power on while triggering multiple calls on it.
ivcam2::group_multiple_fw_calls( _device->get_depth_sensor(), [&]() {
auto min = _hw_monitor->send( command{ AMCGET, _control, get_min } );
auto max = _hw_monitor->send( command{ AMCGET, _control, get_max } );
auto step = _hw_monitor->send( command{ AMCGET, _control, get_step } );

if( min.size() < sizeof( int32_t ) || max.size() < sizeof( int32_t )
|| step.size() < sizeof( int32_t ) )
{
std::stringstream s;
s << "Size of data returned is not valid min size = " << min.size()
<< ", max size = " << max.size() << ", step size = " << step.size();
throw std::runtime_error( s.str() );
}

auto max_value = float( *( reinterpret_cast< int32_t * >( max.data() ) ) );
auto min_value = float( *( reinterpret_cast< int32_t * >( min.data() ) ) );

auto res = query_default();

_range = option_range{ min_value,
max_value,
float( *( reinterpret_cast< int32_t * >( step.data() ) ) ),
res };
} );
}

float amc_option::query() const
{
auto res = _hw_monitor->send( command{ AMCGET, _control, get_current } );

if( res.size() < sizeof( int32_t ) )
{
std::stringstream s;
s << "Size of data returned from query(get_current) of " << _control << " is " << res.size()
<< " while min size = " << sizeof( int32_t );
throw std::runtime_error( s.str() );
}
auto val = *( reinterpret_cast< uint32_t * >( res.data() ) );
return float( val );
}

void amc_option::set( float value )
{
_hw_monitor->send( command{ AMCSET, _control, (int)value } );
}

librealsense::option_range amc_option::get_range() const
{
return _range;
}

float amc_option::query_default() const
{
auto res = _hw_monitor->send( command{ AMCGET, _control, l500_command::get_default } );

auto val = *( reinterpret_cast< uint32_t * >( res.data() ) );
return float( val );
}

void amc_option::enable_recording( std::function< void( const option & ) > recording_action ) {}

65 changes: 65 additions & 0 deletions src/l500/l535-amc-option.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#pragma once
#include "hw-monitor.h"
#include "l500-device.h"

namespace librealsense {
namespace ivcam2 {
namespace l535 {
enum amc_control
{
confidence = 0,
post_processing_sharpness = 1,
pre_processing_sharpness = 2,
noise_filtering = 3,
apd = 4,
laser_gain = 5,
min_distance = 6,
invalidation_bypass = 7,
alternate_ir = 8,
rx_sensitivity = 9,
};

enum amc_command
{
get_current = 0,
get_min = 1,
get_max = 2,
get_step = 3,
get_default = 4
};

class amc_option : public option
{
public:
float query() const override;

void set( float value ) override;

option_range get_range() const override;

bool is_enabled() const override { return true; }

const char * get_description() const override { return _description.c_str(); }

void enable_recording( std::function< void( const option & ) > recording_action ) override;

amc_option( l500_device * l500_dev,
hw_monitor * hw_monitor,
amc_control type,
const std::string & description );

private:
float query_default() const;

amc_control _control;
l500_device * _device;
hw_monitor * _hw_monitor;
option_range _range;
std::string _description;
};
} // namespace l535
} // namespace ivcam2
} // namespace librealsense
71 changes: 71 additions & 0 deletions src/l500/l535-device-options.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
//// License: Apache 2.0. See LICENSE file in root directory.
//// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#include "l535-device-options.h"
#include "l535-amc-option.h"
#include "l535-preset-option.h"
#include "l500-private.h"
#include "l500-depth.h"

using librealsense::ivcam2::l535::device_options;

device_options::device_options( std::shared_ptr< librealsense::context > ctx,
const librealsense::platform::backend_device_group & group )
: device( ctx, group )
, l500_device( ctx, group )
{
auto & raw_depth_sensor = get_raw_depth_sensor();
auto & depth_sensor = get_depth_sensor();

// Keep the USB power on while triggering multiple HW monitor commands on it.
ivcam2::group_multiple_fw_calls( depth_sensor, [&]() {
auto default_sensor_mode = RS2_SENSOR_MODE_VGA;

std::map< rs2_option, std::pair< amc_control, std::string > > options = {
{ RS2_OPTION_POST_PROCESSING_SHARPENING,
{ post_processing_sharpness,
"Changes the amount of sharpening in the post-processed image" } },
{ RS2_OPTION_PRE_PROCESSING_SHARPENING,
{ pre_processing_sharpness,
"Changes the amount of sharpening in the pre-processed image" } },
{ RS2_OPTION_NOISE_FILTERING,
{ noise_filtering, "Control edges and background noise" } },
{ RS2_OPTION_AVALANCHE_PHOTO_DIODE,
{ apd, "Changes the exposure time of Avalanche Photo Diode in the receiver" } },
{ RS2_OPTION_CONFIDENCE_THRESHOLD,
{ confidence,
"The confidence level threshold to use to mark a pixel as valid by the depth "
"algorithm" } },
{ RS2_OPTION_LASER_POWER,
{ laser_gain, "Power of the laser emitter, with 0 meaning projector off" } },
{ RS2_OPTION_MIN_DISTANCE,
{ min_distance, "Minimal distance to the target (in mm)" } },
{ RS2_OPTION_INVALIDATION_BYPASS,
{ invalidation_bypass, "Enable/disable pixel invalidation" } },
{ RS2_OPTION_ALTERNATE_IR,
{ alternate_ir, "Enable/Disable alternate IR" } },
{ RS2_OPTION_AUTO_RX_SENSITIVITY,
{ rx_sensitivity, "auto gain" } } // TODO: replace the description
};

for( auto i : options )
{
auto opt = std::make_shared< amc_option >( this,
_hw_monitor.get(),
i.second.first,
i.second.second );

depth_sensor.register_option( i.first, opt );
_advanced_options.push_back( i.first );
}

auto preset = std::make_shared< preset_option >(
option_range{ RS2_L500_VISUAL_PRESET_CUSTOM,
RS2_L500_VISUAL_PRESET_CUSTOM,
1,
RS2_L500_VISUAL_PRESET_CUSTOM },
"Preset to calibrate the camera" ); //todo:improve the

depth_sensor.register_option( RS2_OPTION_VISUAL_PRESET, preset );
} );
}
20 changes: 20 additions & 0 deletions src/l500/l535-device-options.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#pragma once
#include "hw-monitor.h"
#include "l500-device.h"

namespace librealsense {
namespace ivcam2 {
namespace l535 {

class device_options : public virtual l500_device
{
public:
device_options( std::shared_ptr< context > ctx, const platform::backend_device_group & group );
};

} // namespace l535
} // namespace ivcam2
} // namespace librealsense
29 changes: 29 additions & 0 deletions src/l500/l535-preset-option.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
//// License: Apache 2.0. See LICENSE file in root directory.
//// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#include "l535-preset-option.h"
#include "l500-private.h"
#include "l500-depth.h"

using librealsense::ivcam2::l535::preset_option;

preset_option::preset_option( const librealsense::option_range & range, std::string description )
: float_option_with_description< rs2_l500_visual_preset >( range, description )
{
}

void preset_option::set( float value )
{
if (static_cast<rs2_l500_visual_preset>(int(value)) != RS2_L500_VISUAL_PRESET_CUSTOM)
throw invalid_value_exception(to_string() <<
static_cast<rs2_l500_visual_preset>(int(value)) << "not supported!");

super::set( value );
}

void preset_option::set_value( float value )
{
super::set( value );
}


23 changes: 23 additions & 0 deletions src/l500/l535-preset-option.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#pragma once
#include "hw-monitor.h"
#include "l500-device.h"

namespace librealsense {
namespace ivcam2 {
namespace l535 {

class preset_option : public float_option_with_description< rs2_l500_visual_preset >
{
typedef float_option_with_description< rs2_l500_visual_preset > super;
public:
preset_option( const option_range& range, std::string description );
void set( float value ) override;
void set_value( float value );
};

} // namespace l535
} // namespace ivcam2
} // namespace librealsense
1 change: 1 addition & 0 deletions src/types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -442,6 +442,7 @@ namespace librealsense
case RS2_OPTION_ENABLE_IR_REFLECTIVITY: return "Enable IR Reflectivity";
CASE(AUTO_EXPOSURE_LIMIT)
CASE(AUTO_GAIN_LIMIT)
CASE(AUTO_RX_SENSITIVITY)
default: assert(!is_valid(value)); return UNKNOWN_VALUE;
}
#undef CASE
Expand Down
Loading

0 comments on commit b8ec3b5

Please sign in to comment.