Skip to content

Commit

Permalink
Merge pull request #8087 from Nir-Az/DQT_remove_wrong_default_setting
Browse files Browse the repository at this point in the history
DQT - wrong display of advanced controls for L515 + wrong UI setting when switching devices
  • Loading branch information
ev-mp authored Jan 5, 2021
2 parents 561d79f + 65d1fd7 commit ab319a2
Show file tree
Hide file tree
Showing 3 changed files with 58 additions and 36 deletions.
51 changes: 28 additions & 23 deletions common/model-views.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ using namespace rs400;
using namespace nlohmann;
using namespace rs2::sw_update;

static rs2_sensor_mode resolution_from_width_height(int width, int height)
rs2_sensor_mode rs2::resolution_from_width_height(int width, int height)
{
if ((width == 240 && height == 320) || (width == 320 && height == 240))
return RS2_SENSOR_MODE_QVGA;
Expand Down Expand Up @@ -992,7 +992,8 @@ namespace rs2
std::shared_ptr<sensor> s,
std::shared_ptr< atomic_objects_in_frame > device_detected_objects,
std::string& error_message,
viewer_model& viewer
viewer_model& viewer,
bool new_device_connected
)
: s(s), dev(dev), tm2(), ui(), last_valid_ui(),
streaming(false), _pause(false),
Expand Down Expand Up @@ -1236,23 +1237,26 @@ namespace rs2
get_default_selection_index(res_values, default_resolution, &selection_index);
ui.selected_res_id = selection_index;

// Have the various preset options automatically update based on the resolution of the
// (closed) stream...
// TODO we have no res_values when loading color rosbag, and color sensor isn't
// even supposed to support SENSOR_MODE... see RS5-7726
if( s->supports( RS2_OPTION_SENSOR_MODE ) && !res_values.empty() )
if (new_device_connected)
{
// Watch out for read-only options in the playback sensor!
try
// Have the various preset options automatically update based on the resolution of the
// (closed) stream...
// TODO we have no res_values when loading color rosbag, and color sensor isn't
// even supposed to support SENSOR_MODE... see RS5-7726
if( s->supports( RS2_OPTION_SENSOR_MODE ) && !res_values.empty() )
{
s->set_option( RS2_OPTION_SENSOR_MODE,
static_cast< float >( resolution_from_width_height(
res_values[ui.selected_res_id].first,
res_values[ui.selected_res_id].second ) ) );
}
catch( not_implemented_error const &)
{
// Just ignore for now: need to figure out a way to write to playback sensors...
// Watch out for read-only options in the playback sensor!
try
{
s->set_option( RS2_OPTION_SENSOR_MODE,
static_cast< float >( resolution_from_width_height(
res_values[ui.selected_res_id].first,
res_values[ui.selected_res_id].second ) ) );
}
catch( not_implemented_error const &)
{
// Just ignore for now: need to figure out a way to write to playback sensors...
}
}
}

Expand Down Expand Up @@ -1318,8 +1322,9 @@ namespace rs2
<< s->get_info(RS2_CAMERA_INFO_NAME);

auto streaming_tooltip = [&]() {
if (streaming && ImGui::IsItemHovered())
ImGui::SetTooltip("Can't modify while streaming");
if( ( ! allow_change_resolution_while_streaming && streaming )
&& ImGui::IsItemHovered() )
ImGui::SetTooltip( "Can't modify while streaming" );
};

//ImGui::Columns(2, label.c_str(), false);
Expand All @@ -1338,7 +1343,7 @@ namespace rs2
label = to_string() << "##" << dev.get_info(RS2_CAMERA_INFO_NAME)
<< s->get_info(RS2_CAMERA_INFO_NAME) << " resolution";

if (streaming)
if( ! allow_change_resolution_while_streaming && streaming )
{
ImGui::Text("%s", res_chars[ui.selected_res_id]);
streaming_tooltip();
Expand Down Expand Up @@ -1413,7 +1418,7 @@ namespace rs2
label = to_string() << "##" << dev.get_info(RS2_CAMERA_INFO_NAME)
<< s->get_info(RS2_CAMERA_INFO_NAME) << " fps";

if (streaming)
if( ! allow_change_fps_while_streaming && streaming )
{
ImGui::Text("%s", fps_chars[ui.selected_shared_fps_id]);
streaming_tooltip();
Expand Down Expand Up @@ -3734,7 +3739,7 @@ namespace rs2
}
}

device_model::device_model(device& dev, std::string& error_message, viewer_model& viewer, bool remove)
device_model::device_model(device& dev, std::string& error_message, viewer_model& viewer, bool new_device_connected, bool remove)
: dev(dev),
_calib_model(dev),
syncer(viewer.syncer),
Expand All @@ -3755,7 +3760,7 @@ namespace rs2

for (auto&& sub : dev.query_sensors())
{
auto model = std::make_shared<subdevice_model>(dev, std::make_shared<sensor>(sub), _detected_objects, error_message, viewer);
auto model = std::make_shared<subdevice_model>(dev, std::make_shared<sensor>(sub), _detected_objects, error_message, viewer, new_device_connected);
subdevices.push_back(model);
}

Expand Down
9 changes: 6 additions & 3 deletions common/model-views.h
Original file line number Diff line number Diff line change
Expand Up @@ -268,6 +268,8 @@ namespace rs2

void imgui_easy_theming(ImFont*& font_14, ImFont*& font_18, ImFont*& monofont);

rs2_sensor_mode resolution_from_width_height(int width, int height);

template<class T>
void sort_together(std::vector<T>& vec, std::vector<std::string>& names)
{
Expand Down Expand Up @@ -550,7 +552,7 @@ namespace rs2
bool* options_invalidated,
std::string& error_message);

subdevice_model(device& dev, std::shared_ptr<sensor> s, std::shared_ptr< atomic_objects_in_frame > objects, std::string& error_message, viewer_model& viewer);
subdevice_model(device& dev, std::shared_ptr<sensor> s, std::shared_ptr< atomic_objects_in_frame > objects, std::string& error_message, viewer_model& viewer, bool new_device_connected = true);
~subdevice_model();

bool is_there_common_fps() ;
Expand Down Expand Up @@ -646,7 +648,8 @@ namespace rs2
int next_option = 0;
std::vector<rs2_option> supported_options;
bool streaming = false;

bool allow_change_resolution_while_streaming = false;
bool allow_change_fps_while_streaming = false;
rect normalized_zoom{0, 0, 1, 1};
rect roi_rect;
bool auto_exposure_enabled = false;
Expand Down Expand Up @@ -751,7 +754,7 @@ namespace rs2
typedef std::function<void(std::function<void()> load)> json_loading_func;

void reset();
explicit device_model(device& dev, std::string& error_message, viewer_model& viewer, bool allow_remove=true);
explicit device_model(device& dev, std::string& error_message, viewer_model& viewer, bool new_device_connected = true, bool allow_remove=true);
~device_model();
void start_recording(const std::string& path, std::string& error_message);
void stop_recording(viewer_model& viewer);
Expand Down
34 changes: 24 additions & 10 deletions tools/depth-quality/depth-quality-model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -841,10 +841,15 @@ namespace rs2
bool save = false;
subdevice_ui_selection prev_ui;

if (_depth_sensor_model)
auto dev = _pipe.get_active_profile().get_device();

if (_device_model && _depth_sensor_model)
{
prev_ui = _depth_sensor_model->last_valid_ui;
save = true;
if( ! _first_frame )
{
prev_ui = _depth_sensor_model->last_valid_ui;
save = true;
}

// Clean-up the models for new configuration
for (auto&& s : _device_model->subdevices)
Expand All @@ -854,21 +859,30 @@ namespace rs2
_viewer_model.selected_depth_source_uid = -1;
_viewer_model.selected_tex_source_uid = -1;
}

auto dev = _pipe.get_active_profile().get_device();
auto dpt_sensor = std::make_shared<sensor>(dev.first<depth_sensor>());
_device_model = std::shared_ptr<rs2::device_model>(new device_model(dev, _error_message, _viewer_model,false));
// Create a new device model - reset all UI the new device
_device_model = std::shared_ptr<rs2::device_model>(new device_model(dev, _error_message, _viewer_model, _first_frame, false));

// Get device depth sensor model
for (auto&& sub : _device_model->subdevices)
{
if (sub->s->is<depth_sensor>())
{
_depth_sensor_model = sub;
break;
}
}

_device_model->show_depth_only = true;
_device_model->show_stream_selection = false;
std::shared_ptr< atomic_objects_in_frame > no_detected_objects;
_depth_sensor_model = std::make_shared<rs2::subdevice_model>(dev, dpt_sensor, no_detected_objects, _error_message, _viewer_model);

_depth_sensor_model->draw_streams_selector = false;
_depth_sensor_model->draw_fps_selector = true;
_depth_sensor_model->allow_change_resolution_while_streaming = true;
_depth_sensor_model->allow_change_fps_while_streaming = true;

// Retrieve stereo baseline for supported devices
auto baseline_mm = -1.f;
auto profiles = dpt_sensor->get_stream_profiles();
auto profiles = _depth_sensor_model->s->get_stream_profiles();
auto right_sensor = std::find_if(profiles.begin(), profiles.end(), [](rs2::stream_profile& p)
{ return (p.stream_index() == 2) && (p.stream_type() == RS2_STREAM_INFRARED); });

Expand Down

0 comments on commit ab319a2

Please sign in to comment.