Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add description to l500-options #7474

Merged
merged 3 commits into from
Oct 18, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
34 changes: 23 additions & 11 deletions src/l500/l500-depth.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,17 +76,29 @@ namespace librealsense
auto& depth_sensor = get_depth_sensor();
auto& raw_depth_sensor = get_raw_depth_sensor();

depth_sensor.register_option(RS2_OPTION_LLD_TEMPERATURE,
std::make_shared <l500_temperature_options>(_hw_monitor.get(), RS2_OPTION_LLD_TEMPERATURE));

depth_sensor.register_option(RS2_OPTION_MC_TEMPERATURE,
std::make_shared <l500_temperature_options>(_hw_monitor.get(), RS2_OPTION_MC_TEMPERATURE));

depth_sensor.register_option(RS2_OPTION_MA_TEMPERATURE,
std::make_shared <l500_temperature_options>(_hw_monitor.get(), RS2_OPTION_MA_TEMPERATURE));

depth_sensor.register_option(RS2_OPTION_APD_TEMPERATURE,
std::make_shared <l500_temperature_options>(_hw_monitor.get(), RS2_OPTION_APD_TEMPERATURE));
depth_sensor.register_option(
RS2_OPTION_LLD_TEMPERATURE,
std::make_shared< l500_temperature_options >( _hw_monitor.get(),
RS2_OPTION_LLD_TEMPERATURE,
"Laser Driver temperature" ) );

depth_sensor.register_option(
RS2_OPTION_MC_TEMPERATURE,
std::make_shared< l500_temperature_options >( _hw_monitor.get(),
RS2_OPTION_MC_TEMPERATURE,
"Mems Controller temperature" ) );

depth_sensor.register_option(
RS2_OPTION_MA_TEMPERATURE,
std::make_shared< l500_temperature_options >( _hw_monitor.get(),
RS2_OPTION_MA_TEMPERATURE,
"DSP controller temperature" ) );

depth_sensor.register_option(
RS2_OPTION_APD_TEMPERATURE,
std::make_shared< l500_temperature_options >( _hw_monitor.get(),
RS2_OPTION_APD_TEMPERATURE,
"Avalanche Photo Diode temperature" ) );

environment::get_instance().get_extrinsics_graph().register_same_extrinsics(*_depth_stream, *_ir_stream);
environment::get_instance().get_extrinsics_graph().register_same_extrinsics(*_depth_stream, *_confidence_stream);
Expand Down
105 changes: 94 additions & 11 deletions src/l500/l500-options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,13 @@ namespace librealsense
return _range;
}

l500_hw_options::l500_hw_options(hw_monitor* hw_monitor, l500_control type, option* resolution)
l500_hw_options::l500_hw_options( hw_monitor * hw_monitor,
l500_control type,
option * resolution,
std::string description )
maloel marked this conversation as resolved.
Show resolved Hide resolved
:_hw_monitor(hw_monitor),
_type(type),
_resolution(resolution)
_type(type), _resolution( resolution )
, _description( description )
{
auto min = _hw_monitor->send(command{ AMCGET, _type, get_min });
auto max = _hw_monitor->send(command{ AMCGET, _type, get_max });
Expand Down Expand Up @@ -97,14 +100,94 @@ namespace librealsense

depth_sensor.register_option(RS2_OPTION_SENSOR_MODE, resolution_option);

_hw_options[RS2_OPTION_POST_PROCESSING_SHARPENING] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_POST_PROCESSING_SHARPENING, _hw_monitor.get(), post_processing_sharpness, resolution_option.get());
_hw_options[RS2_OPTION_PRE_PROCESSING_SHARPENING] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_PRE_PROCESSING_SHARPENING, _hw_monitor.get(), pre_processing_sharpness, resolution_option.get());
_hw_options[RS2_OPTION_NOISE_FILTERING] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_NOISE_FILTERING, _hw_monitor.get(), noise_filtering, resolution_option.get());
_hw_options[RS2_OPTION_AVALANCHE_PHOTO_DIODE] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_AVALANCHE_PHOTO_DIODE, _hw_monitor.get(), apd, resolution_option.get());
_hw_options[RS2_OPTION_CONFIDENCE_THRESHOLD] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_CONFIDENCE_THRESHOLD, _hw_monitor.get(), confidence, resolution_option.get());
_hw_options[RS2_OPTION_LASER_POWER] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_LASER_POWER, _hw_monitor.get(), laser_gain, resolution_option.get());
_hw_options[RS2_OPTION_MIN_DISTANCE] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_MIN_DISTANCE, _hw_monitor.get(), min_distance, resolution_option.get());
_hw_options[RS2_OPTION_INVALIDATION_BYPASS] = register_option<l500_hw_options, hw_monitor*, l500_control, option*>(RS2_OPTION_INVALIDATION_BYPASS, _hw_monitor.get(), invalidation_bypass, resolution_option.get());
_hw_options[RS2_OPTION_POST_PROCESSING_SHARPENING] = register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >(
RS2_OPTION_POST_PROCESSING_SHARPENING,
_hw_monitor.get(),
post_processing_sharpness,
resolution_option.get(),
"Changes the amount of sharpening in the post-processed image" );

_hw_options[RS2_OPTION_PRE_PROCESSING_SHARPENING] = register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >(
RS2_OPTION_PRE_PROCESSING_SHARPENING,
_hw_monitor.get(),
pre_processing_sharpness,
resolution_option.get(),
"Changes the amount of sharpening in the pre-processed image" );

_hw_options[RS2_OPTION_NOISE_FILTERING]
= register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >( RS2_OPTION_NOISE_FILTERING,
_hw_monitor.get(),
noise_filtering,
resolution_option.get(),
"Control edges and background noise" );

_hw_options[RS2_OPTION_AVALANCHE_PHOTO_DIODE] = register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >(
RS2_OPTION_AVALANCHE_PHOTO_DIODE,
_hw_monitor.get(),
apd,
resolution_option.get(),
"Changes the exposure time of Avalanche Photo Diode in the receiver" );

_hw_options[RS2_OPTION_CONFIDENCE_THRESHOLD] = register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >(
RS2_OPTION_CONFIDENCE_THRESHOLD,
_hw_monitor.get(),
confidence,
resolution_option.get(),
"The confidence level threshold used by the Depth algorithm pipe to set whether a "
maloel marked this conversation as resolved.
Show resolved Hide resolved
"pixel will get a valid range or will be marked with invalid range" );

_hw_options[RS2_OPTION_LASER_POWER] = register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >(
RS2_OPTION_LASER_POWER,
_hw_monitor.get(),
laser_gain,
resolution_option.get(),
"Power of the laser emitter, with 0 meaning projector off" );

_hw_options[RS2_OPTION_MIN_DISTANCE]
= register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >( RS2_OPTION_MIN_DISTANCE,
_hw_monitor.get(),
min_distance,
resolution_option.get(),
"Minimal distance to the target" );
Copy link
Collaborator

Choose a reason for hiding this comment

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

What unit?


_hw_options[RS2_OPTION_INVALIDATION_BYPASS]
= register_option< l500_hw_options,
hw_monitor *,
l500_control,
option *,
std::string >( RS2_OPTION_INVALIDATION_BYPASS,
_hw_monitor.get(),
invalidation_bypass,
resolution_option.get(),
"Enable\disable pixel invalidation" );
maloel marked this conversation as resolved.
Show resolved Hide resolved

_ambient_light = register_option<uvc_xu_option<int>, uvc_sensor&, platform::extension_unit, uint8_t, std::string, const std::map<float, std::string>& >
(RS2_OPTION_AMBIENT_LIGHT, raw_depth_sensor, ivcam2::depth_xu, ivcam2::L500_AMBIENT,
Expand Down
9 changes: 7 additions & 2 deletions src/l500/l500-options.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,15 @@ namespace librealsense

bool is_enabled() const override { return true; }

const char* get_description() const override { return ""; }

l500_hw_options(hw_monitor* hw_monitor, l500_control type, option* resolution);
const char * get_description() const override { return _description.c_str(); }

void enable_recording(std::function<void(const option&)> recording_action) override;
l500_hw_options( hw_monitor * hw_monitor,
l500_control type,
option * resolution,
std::string description );
maloel marked this conversation as resolved.
Show resolved Hide resolved


private:
float query(int width) const;
Expand All @@ -53,6 +57,7 @@ namespace librealsense
uint32_t _width;
uint32_t _height;
option* _resolution;
std::string _description;
};

class l500_options: public virtual l500_device
Expand Down
8 changes: 6 additions & 2 deletions src/l500/l500-private.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,12 @@ namespace librealsense
}
}

l500_temperature_options::l500_temperature_options(hw_monitor* hw_monitor, rs2_option opt)
:_hw_monitor(hw_monitor), _option(opt)
l500_temperature_options::l500_temperature_options( hw_monitor * hw_monitor,
rs2_option opt,
std::string description )
: _hw_monitor( hw_monitor )
, _option( opt )
, _description( description )
{
}

Expand Down
7 changes: 5 additions & 2 deletions src/l500/l500-private.h
Original file line number Diff line number Diff line change
Expand Up @@ -398,13 +398,16 @@ namespace librealsense

bool is_enabled() const override { return true; }

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

explicit l500_temperature_options(hw_monitor* hw_monitor, rs2_option opt);
explicit l500_temperature_options( hw_monitor * hw_monitor,
rs2_option opt,
std::string description );
maloel marked this conversation as resolved.
Show resolved Hide resolved

private:
rs2_option _option;
hw_monitor* _hw_monitor;
std::string _description;
};

class l500_timestamp_reader : public frame_timestamp_reader
Expand Down