From f80dd790f052483ff3b34d2feec9b78f137685ad Mon Sep 17 00:00:00 2001 From: "Dorodnicov, Sergey" Date: Sun, 15 Sep 2019 08:09:52 -0700 Subject: [PATCH 1/4] Auto-calibration adjustments --- common/fw-update-helper.cpp | 4 +- common/model-views.cpp | 6 ++- common/on-chip-calib.cpp | 80 +++++++++++++++++++++++++++---------- src/ds5/ds5-color.cpp | 5 +++ 4 files changed, 71 insertions(+), 24 deletions(-) diff --git a/common/fw-update-helper.cpp b/common/fw-update-helper.cpp index d4ed2c99b2..f43a1fb7b2 100644 --- a/common/fw-update-helper.cpp +++ b/common/fw-update-helper.cpp @@ -56,7 +56,9 @@ namespace rs2 if (product_line == RS2_PRODUCT_LINE_D400 && allow_rc_firmware) return FW_D4XX_RC_IMAGE_VERSION; else if (product_line == RS2_PRODUCT_LINE_D400) return FW_D4XX_FW_IMAGE_VERSION; - else if (product_line == RS2_PRODUCT_LINE_SR300) return FW_SR3XX_FW_IMAGE_VERSION; + // NOTE: For now removing recommended firmware version for SR30x series + // TODO: Re-enable in future release + //else if (product_line == RS2_PRODUCT_LINE_SR300) return FW_SR3XX_FW_IMAGE_VERSION; else return ""; } diff --git a/common/model-views.cpp b/common/model-views.cpp index 4377cf05ab..a08c585ef6 100644 --- a/common/model-views.cpp +++ b/common/model-views.cpp @@ -3030,8 +3030,10 @@ namespace rs2 n->snoozed = true; } - viewer.not_model.add_notification(n); - related_notifications.push_back(n); + // NOTE: For now do not pre-emptively suggest auto-calibration + // TODO: Revert in later release + //viewer.not_model.add_notification(n); + //related_notifications.push_back(n); } } } diff --git a/common/on-chip-calib.cpp b/common/on-chip-calib.cpp index ee7dbcaf4a..3da9831bdc 100644 --- a/common/on-chip-calib.cpp +++ b/common/on-chip-calib.cpp @@ -428,7 +428,7 @@ namespace rs2 { std::this_thread::sleep_for(std::chrono::milliseconds(200)); - uint8_t speed = 4 - _speed; + uint8_t speed = 4; // NOTE: Start the calibration in slow mode bool repeat = true; while (repeat) // Repeat until we got a result @@ -875,9 +875,45 @@ namespace rs2 ImGui::SetCursorScreenPos({ float(x + 15), float(y + 33) }); - if (!recommend_keep) ImGui::Text("%s", "Camera original calibration is OK"); - else if (health > 0.2f) ImGui::Text("%s", "We found much better calibration!"); - else ImGui::Text("%s", "We found better calibration for the device!"); + ImGui::Text("Calibration Status: "); + + std::stringstream ss; ss << std::fixed << std::setprecision(2) << health; + auto health_str = ss.str(); + + std::string text_name = to_string() << "##notification_text_" << index; + + ImGui::SetCursorScreenPos({ float(x + 136), float(y + 30) }); + ImGui::PushStyleColor(ImGuiCol_Text, white); + ImGui::PushStyleColor(ImGuiCol_FrameBg, transparent); + ImGui::PushStyleColor(ImGuiCol_ScrollbarBg, transparent); + ImGui::PushStyleColor(ImGuiCol_ScrollbarGrab, transparent); + ImGui::PushStyleColor(ImGuiCol_ScrollbarGrabActive, transparent); + ImGui::PushStyleColor(ImGuiCol_ScrollbarGrabHovered, transparent); + ImGui::PushStyleColor(ImGuiCol_TextSelectedBg, white); + ImGui::InputTextMultiline(text_name.c_str(), const_cast(health_str.c_str()), + strlen(health_str.c_str()) + 1, { 50, + ImGui::GetTextLineHeight() + 6 }, + ImGuiInputTextFlags_ReadOnly); + ImGui::PopStyleColor(7); + + ImGui::SetCursorScreenPos({ float(x + 172), float(y + 33) }); + + if (!recommend_keep) + { + ImGui::PushStyleColor(ImGuiCol_Text, greenish); + ImGui::Text("(Good)"); + } + else if (health < 0.25f) + { + ImGui::PushStyleColor(ImGuiCol_Text, yellowish); + ImGui::Text("(Can be Improved)"); + } + else + { + ImGui::PushStyleColor(ImGuiCol_Text, redish); + ImGui::Text("(Requires Calibration)"); + } + ImGui::PopStyleColor(); auto old_fr = get_manager().get_metric(false).first; auto new_fr = get_manager().get_metric(true).first; @@ -901,7 +937,9 @@ namespace rs2 new_units = "cm"; } - if (fr_improvement > 1.f || rms_improvement > 1.f) + // NOTE: Disabling metrics temporarily + // TODO: Re-enable in future release + if (/* fr_improvement > 1.f || rms_improvement > 1.f */ false) { std::string txt = to_string() << " Fill-Rate: " << std::setprecision(1) << std::fixed << new_fr << "%%"; @@ -985,29 +1023,29 @@ namespace rs2 { ImGui::PushStyleColor(ImGuiCol_Button, saturate(sensor_header_light_blue, sat)); ImGui::PushStyleColor(ImGuiCol_ButtonHovered, saturate(sensor_header_light_blue, 1.5f)); - } - std::string button_name = to_string() << "Apply New" << "##apply" << index; - if (!use_new_calib) button_name = to_string() << "Keep Original" << "##original" << index; + std::string button_name = to_string() << "Apply New" << "##apply" << index; + if (!use_new_calib) button_name = to_string() << "Keep Original" << "##original" << index; - ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) }); - if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f })) - { - if (use_new_calib) + ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) }); + if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f })) { - get_manager().keep(); - update_state = RS2_CALIB_STATE_COMPLETE; - pinned = false; - enable_dismiss = false; - last_progress_time = last_interacted = system_clock::now() + milliseconds(500); + if (use_new_calib) + { + get_manager().keep(); + update_state = RS2_CALIB_STATE_COMPLETE; + pinned = false; + enable_dismiss = false; + last_progress_time = last_interacted = system_clock::now() + milliseconds(500); + } + else dismiss(false); + + get_manager().restore_workspace([this](std::function a) { a(); }); } - else dismiss(false); - get_manager().restore_workspace([this](std::function a){ a(); }); + ImGui::PopStyleColor(2); } - if (recommend_keep) ImGui::PopStyleColor(2); - if (ImGui::IsItemHovered()) { ImGui::SetTooltip("%s", "New calibration values will be saved in device memory"); diff --git a/src/ds5/ds5-color.cpp b/src/ds5/ds5-color.cpp index 3618183dd6..b7ad1cc7fd 100644 --- a/src/ds5/ds5-color.cpp +++ b/src/ds5/ds5-color.cpp @@ -74,6 +74,11 @@ namespace librealsense color_ep->register_pu(RS2_OPTION_BACKLIGHT_COMPENSATION); color_ep->register_pu(RS2_OPTION_AUTO_EXPOSURE_PRIORITY); } + // From 5.11.15 auto-exposure priority is supported on the D465 + else if (_fw_version >= firmware_version("5.11.15.0")) + { + color_ep->register_pu(RS2_OPTION_AUTO_EXPOSURE_PRIORITY); + } if (color_devices_info.front().pid == ds::RS465_PID) color_ep->register_pixel_format(pf_mjpg); From f96a16960992a12904ebf48078cb90c981af0735 Mon Sep 17 00:00:00 2001 From: "Dorodnicov, Sergey" Date: Mon, 16 Sep 2019 05:10:01 -0700 Subject: [PATCH 2/4] More minor fixes to auto-calibration --- common/model-views.cpp | 4 +- common/on-chip-calib.cpp | 338 ++++++++++++++++++++++----------------- common/on-chip-calib.h | 7 +- common/viewer.cpp | 8 +- 4 files changed, 198 insertions(+), 159 deletions(-) diff --git a/common/model-views.cpp b/common/model-views.cpp index a08c585ef6..d42b68962f 100644 --- a/common/model-views.cpp +++ b/common/model-views.cpp @@ -4383,13 +4383,11 @@ namespace rs2 viewer.not_model.add_notification(n); n->forced = true; - n->update_state = autocalib_notification_model::RS2_CALIB_STATE_CALIB_IN_PROCESS; + n->update_state = autocalib_notification_model::RS2_CALIB_STATE_SELF_INPUT; for (auto&& n : related_notifications) if (dynamic_cast(n.get())) n->dismiss(false); - - manager->start(n); } catch (const error& e) { diff --git a/common/on-chip-calib.cpp b/common/on-chip-calib.cpp index 3da9831bdc..bf63b0b7a2 100644 --- a/common/on-chip-calib.cpp +++ b/common/on-chip-calib.cpp @@ -412,7 +412,7 @@ namespace rs2 log(to_string() << "Warning: " << ex.what()); } - _progress = count * (2 * _speed); + _progress = count * (2 * speed); } while (count++ < 200 && !done); // If we exit due to counter, report timeout @@ -428,86 +428,67 @@ namespace rs2 { std::this_thread::sleep_for(std::chrono::milliseconds(200)); - uint8_t speed = 4; // NOTE: Start the calibration in slow mode + // Begin auto-calibration + std::vector cmd = + { + 0x14, 0x00, 0xab, 0xcd, + 0x80, 0x00, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x00, + (uint8_t)speed, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00 + }; + + safe_send_command(cmd, "START_CALIB"); - bool repeat = true; - while (repeat) // Repeat until we got a result + memset(&result, 0, sizeof(DirectSearchCalibrationResult)); + + // While not ready... + int count = 0; + bool done = false; + do { - // Begin auto-calibration - std::vector cmd = + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + + // Check calibration status + cmd = { 0x14, 0x00, 0xab, 0xcd, 0x80, 0x00, 0x00, 0x00, - 0x08, 0x00, 0x00, 0x00, - speed, 0x00, 0x00, 0x00, + 0x03, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; - safe_send_command(cmd, "START_CALIB"); - - memset(&result, 0, sizeof(DirectSearchCalibrationResult)); - - // While not ready... - int count = 0; - bool done = false; - do + try { - std::this_thread::sleep_for(std::chrono::milliseconds(200)); - - // Check calibration status - cmd = - { - 0x14, 0x00, 0xab, 0xcd, - 0x80, 0x00, 0x00, 0x00, - 0x03, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00 - }; - - try - { - auto res = safe_send_command(cmd, "CALIB_STATUS"); - - if (res.size() < sizeof(int32_t) + sizeof(DirectSearchCalibrationResult)) - throw std::runtime_error("Not enough data from CALIB_STATUS!"); - - result = *reinterpret_cast(res.data()); - done = result.status != RS2_DSC_STATUS_RESULT_NOT_READY; - } - catch (const std::exception& ex) - { - log(to_string() << "Warning: " << ex.what()); - } - - _progress = count * (2 * _speed); + auto res = safe_send_command(cmd, "CALIB_STATUS"); - } while (count++ < 200 && !done); + if (res.size() < sizeof(int32_t) + sizeof(DirectSearchCalibrationResult)) + throw std::runtime_error("Not enough data from CALIB_STATUS!"); - // If we exit due to counter, report timeout - if (!done) + result = *reinterpret_cast(res.data()); + done = result.status != RS2_DSC_STATUS_RESULT_NOT_READY; + } + catch (const std::exception& ex) { - throw std::runtime_error("Operation timed-out!\n" - "Calibration state did not converged in time"); + log(to_string() << "Warning: " << ex.what()); } - std::this_thread::sleep_for(std::chrono::milliseconds(100)); + _progress = count * (2 * speed); - if (result.status != RS2_DSC_STATUS_EDGE_TOO_CLOSE) - { - repeat = false; - } - else - { - // Edge to Close means not enough "samples" to identify fit curve - // Slow down to capture more samples next cycle - log("Edge too close... Slowing down"); - speed++; - if (speed > 4) repeat = false; - } + } while (count++ < 200 && !done); + + // If we exit due to counter, report timeout + if (!done) + { + throw std::runtime_error("Operation timed-out!\n" + "Calibration state did not converged in time"); } + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + status = (rs2_dsc_status)result.status; } @@ -543,7 +524,7 @@ namespace rs2 { update_last_used(); - log(to_string() << "Starting calibration at speed " << _speed); + log(to_string() << "Starting calibration at speed " << speed); _in_3d_view = _viewer.is_3d_view; _viewer.is_3d_view = true; @@ -588,6 +569,16 @@ namespace rs2 // Switch into special Auto-Calibration mode start_viewer(256, 144, 90, invoke); + if (speed == 4) // White-wall + { + if (_sub->s->supports(RS2_OPTION_VISUAL_PRESET)) + { + log("Switching into High-Quality preset for White-Wall mode"); + _sub->s->set_option(RS2_OPTION_VISUAL_PRESET, 3.f); + std::this_thread::sleep_for(std::chrono::milliseconds(200)); + } + } + calibrate(); // Get new calibration from the firmware @@ -719,7 +710,8 @@ namespace rs2 if (update_state == RS2_CALIB_STATE_INITIAL_PROMPT) ImGui::Text("%s", "Calibration Health-Check"); else if (update_state == RS2_CALIB_STATE_CALIB_IN_PROCESS || - update_state == RS2_CALIB_STATE_CALIB_COMPLETE) + update_state == RS2_CALIB_STATE_CALIB_COMPLETE || + update_state == RS2_CALIB_STATE_SELF_INPUT) ImGui::Text("%s", "On-Chip Calibration"); else if (update_state == RS2_CALIB_STATE_TARE_INPUT) ImGui::Text("%s", "Tare Calibration"); @@ -839,6 +831,47 @@ namespace rs2 ImGui::SetTooltip("%s", "Begin Tare Calibration"); } } + else if (update_state == RS2_CALIB_STATE_SELF_INPUT) + { + ImGui::SetCursorScreenPos({ float(x + 9), float(y + 33) }); + ImGui::Text("%s", "Speed:"); + + ImGui::SetCursorScreenPos({ float(x + 135), float(y + 30) }); + + std::string id = to_string() << "##speed_" << index; + + std::vector vals{ "Very Fast", "Fast", "Medium", "Slow", "White Wall" }; + std::vector vals_cstr; + for (auto&& s : vals) vals_cstr.push_back(s.c_str()); + + ImGui::PushItemWidth(width - 145); + ImGui::Combo(id.c_str(), &get_manager().speed, vals_cstr.data(), vals.size()); + ImGui::PopItemWidth(); + + auto sat = 1.f + sin(duration_cast(system_clock::now() - created_time).count() / 700.f) * 0.1f; + + ImGui::PushStyleColor(ImGuiCol_Button, saturate(sensor_header_light_blue, sat)); + ImGui::PushStyleColor(ImGuiCol_ButtonHovered, saturate(sensor_header_light_blue, 1.5f)); + + std::string button_name = to_string() << "Calibrate" << "##self" << index; + + ImGui::SetCursorScreenPos({ float(x + 5), float(y + height - 25) }); + if (ImGui::Button(button_name.c_str(), { float(bar_width), 20.f })) + { + get_manager().restore_workspace([this](std::function a) { a(); }); + get_manager().reset(); + get_manager().start(shared_from_this()); + update_state = RS2_CALIB_STATE_CALIB_IN_PROCESS; + enable_dismiss = false; + } + + ImGui::PopStyleColor(2); + + if (ImGui::IsItemHovered()) + { + ImGui::SetTooltip("%s", "Begin On-Chip Calibration"); + } + } else if (update_state == RS2_CALIB_STATE_FAILED) { ImGui::Text("%s", _error_message.c_str()); @@ -871,11 +904,11 @@ namespace rs2 { auto health = get_manager().get_health(); - auto recommend_keep = health > 0.1f; + auto recommend_keep = health > 0.15f; ImGui::SetCursorScreenPos({ float(x + 15), float(y + 33) }); - ImGui::Text("Calibration Status: "); + ImGui::Text("Calibration Error: "); std::stringstream ss; ss << std::fixed << std::setprecision(2) << health; auto health_str = ss.str(); @@ -900,7 +933,7 @@ namespace rs2 if (!recommend_keep) { - ImGui::PushStyleColor(ImGuiCol_Text, greenish); + ImGui::PushStyleColor(ImGuiCol_Text, light_blue); ImGui::Text("(Good)"); } else if (health < 0.25f) @@ -914,75 +947,57 @@ namespace rs2 ImGui::Text("(Requires Calibration)"); } ImGui::PopStyleColor(); - - auto old_fr = get_manager().get_metric(false).first; - auto new_fr = get_manager().get_metric(true).first; - - auto old_rms = fabs(get_manager().get_metric(false).second); - auto new_rms = fabs(get_manager().get_metric(true).second); - auto fr_improvement = 100.f * ((new_fr - old_fr) / old_fr); - auto rms_improvement = 100.f * ((old_rms - new_rms) / old_rms); - - std::string old_units = "mm"; - if (old_rms > 10.f) - { - old_rms /= 10.f; - old_units = "cm"; - } - std::string new_units = "mm"; - if (new_rms > 10.f) + if (ImGui::IsItemHovered()) { - new_rms /= 10.f; - new_units = "cm"; + ImGui::SetTooltip("%s", "Calibration error captures how far camera calibration is from the optimal one\n" + "[0, 0.15) - Good\n" + "[0.15, 0.25) - Can be Improved\n" + "[0.25, ) - Requires Calibration"); } - // NOTE: Disabling metrics temporarily - // TODO: Re-enable in future release - if (/* fr_improvement > 1.f || rms_improvement > 1.f */ false) + if (recommend_keep) { - std::string txt = to_string() << " Fill-Rate: " << std::setprecision(1) << std::fixed << new_fr << "%%"; - - if (!use_new_calib) - { - txt = to_string() << " Fill-Rate: " << std::setprecision(1) << std::fixed << old_fr << "%%\n"; - } + + auto old_fr = get_manager().get_metric(false).first; + auto new_fr = get_manager().get_metric(true).first; - ImGui::SetCursorScreenPos({ float(x + 12), float(y + 90) }); - ImGui::PushFont(win.get_large_font()); - ImGui::Text("%s", static_cast(textual_icons::check)); - ImGui::PopFont(); + auto old_rms = fabs(get_manager().get_metric(false).second); + auto new_rms = fabs(get_manager().get_metric(true).second); - ImGui::SetCursorScreenPos({ float(x + 35), float(y + 92) }); - ImGui::Text("%s", txt.c_str()); + auto fr_improvement = 100.f * ((new_fr - old_fr) / old_fr); + auto rms_improvement = 100.f * ((old_rms - new_rms) / old_rms); - if (use_new_calib) + std::string old_units = "mm"; + if (old_rms > 10.f) { - ImGui::SameLine(); - - ImGui::PushStyleColor(ImGuiCol_Text, white); - txt = to_string() << " ( +" << std::fixed << std::setprecision(0) << fr_improvement << "%% )"; - ImGui::Text("%s", txt.c_str()); - ImGui::PopStyleColor(); + old_rms /= 10.f; + old_units = "cm"; + } + std::string new_units = "mm"; + if (new_rms > 10.f) + { + new_rms /= 10.f; + new_units = "cm"; } - if (rms_improvement > 1.f) + // NOTE: Disabling metrics temporarily + // TODO: Re-enable in future release + if (/* fr_improvement > 1.f || rms_improvement > 1.f */ false) { - if (use_new_calib) - { - txt = to_string() << " Noise Estimate: " << std::setprecision(2) << std::fixed << new_rms << new_units; - } - else + std::string txt = to_string() << " Fill-Rate: " << std::setprecision(1) << std::fixed << new_fr << "%%"; + + if (!use_new_calib) { - txt = to_string() << " Noise Estimate: " << std::setprecision(2) << std::fixed << old_rms << old_units; + txt = to_string() << " Fill-Rate: " << std::setprecision(1) << std::fixed << old_fr << "%%\n"; } - ImGui::SetCursorScreenPos({ float(x + 12), float(y + 90 + ImGui::GetTextLineHeight() + 6) }); + ImGui::SetCursorScreenPos({ float(x + 12), float(y + 90) }); ImGui::PushFont(win.get_large_font()); ImGui::Text("%s", static_cast(textual_icons::check)); ImGui::PopFont(); - ImGui::SetCursorScreenPos({ float(x + 35), float(y + 92 + ImGui::GetTextLineHeight() + 6) }); + ImGui::SetCursorScreenPos({ float(x + 35), float(y + 92) }); ImGui::Text("%s", txt.c_str()); if (use_new_calib) @@ -990,37 +1005,65 @@ namespace rs2 ImGui::SameLine(); ImGui::PushStyleColor(ImGuiCol_Text, white); - txt = to_string() << " ( -" << std::setprecision(0) << std::fixed << rms_improvement << "%% )"; + txt = to_string() << " ( +" << std::fixed << std::setprecision(0) << fr_improvement << "%% )"; ImGui::Text("%s", txt.c_str()); ImGui::PopStyleColor(); } + + if (rms_improvement > 1.f) + { + if (use_new_calib) + { + txt = to_string() << " Noise Estimate: " << std::setprecision(2) << std::fixed << new_rms << new_units; + } + else + { + txt = to_string() << " Noise Estimate: " << std::setprecision(2) << std::fixed << old_rms << old_units; + } + + ImGui::SetCursorScreenPos({ float(x + 12), float(y + 90 + ImGui::GetTextLineHeight() + 6) }); + ImGui::PushFont(win.get_large_font()); + ImGui::Text("%s", static_cast(textual_icons::check)); + ImGui::PopFont(); + + ImGui::SetCursorScreenPos({ float(x + 35), float(y + 92 + ImGui::GetTextLineHeight() + 6) }); + ImGui::Text("%s", txt.c_str()); + + if (use_new_calib) + { + ImGui::SameLine(); + + ImGui::PushStyleColor(ImGuiCol_Text, white); + txt = to_string() << " ( -" << std::setprecision(0) << std::fixed << rms_improvement << "%% )"; + ImGui::Text("%s", txt.c_str()); + ImGui::PopStyleColor(); + } + } + } + else + { + ImGui::SetCursorScreenPos({ float(x + 12), float(y + 100) }); + ImGui::Text("%s", "Please compare new vs old calibration\nand decide if to keep or discard the result..."); } - } - else - { - ImGui::SetCursorScreenPos({ float(x + 12), float(y + 100) }); - ImGui::Text("%s", "Please compare new vs old calibration\nand decide if to keep or discard the result..."); - } - ImGui::SetCursorScreenPos({ float(x + 9), float(y + 60) }); + ImGui::SetCursorScreenPos({ float(x + 9), float(y + 60) }); - if (ImGui::RadioButton("New", use_new_calib)) - { - use_new_calib = true; - get_manager().apply_calib(true); - } + if (ImGui::RadioButton("New", use_new_calib)) + { + use_new_calib = true; + get_manager().apply_calib(true); + } - ImGui::SetCursorScreenPos({ float(x + 150), float(y + 60) }); - if (ImGui::RadioButton("Original", !use_new_calib)) - { - use_new_calib = false; - get_manager().apply_calib(false); - } + ImGui::SetCursorScreenPos({ float(x + 150), float(y + 60) }); + if (ImGui::RadioButton("Original", !use_new_calib)) + { + use_new_calib = false; + get_manager().apply_calib(false); + } - auto sat = 1.f + sin(duration_cast(system_clock::now() - created_time).count() / 700.f) * 0.1f; + auto sat = 1.f + sin(duration_cast(system_clock::now() - created_time).count() / 700.f) * 0.1f; - if (recommend_keep) - { + ImGui::PushStyleColor(ImGuiCol_Button, saturate(sensor_header_light_blue, sat)); ImGui::PushStyleColor(ImGuiCol_ButtonHovered, saturate(sensor_header_light_blue, 1.5f)); @@ -1044,11 +1087,11 @@ namespace rs2 } ImGui::PopStyleColor(2); - } - if (ImGui::IsItemHovered()) - { - ImGui::SetTooltip("%s", "New calibration values will be saved in device memory"); + if (ImGui::IsItemHovered()) + { + ImGui::SetTooltip("%s", "New calibration values will be saved in device memory"); + } } } @@ -1226,7 +1269,12 @@ namespace rs2 { if (update_state == RS2_CALIB_STATE_COMPLETE) return 65; else if (update_state == RS2_CALIB_STATE_INITIAL_PROMPT) return 120; - else if (update_state == RS2_CALIB_STATE_CALIB_COMPLETE) return 170; + else if (update_state == RS2_CALIB_STATE_CALIB_COMPLETE) + { + if (get_manager().get_health() > 0.15f) return 170; + else return 80; + } + else if (update_state == RS2_CALIB_STATE_SELF_INPUT) return 85; else if (update_state == RS2_CALIB_STATE_TARE_INPUT) return 160; else return 100; } diff --git a/common/on-chip-calib.h b/common/on-chip-calib.h index 19be61754e..2020ca938b 100644 --- a/common/on-chip-calib.h +++ b/common/on-chip-calib.h @@ -31,10 +31,6 @@ namespace rs2 // Get health number from the calibration summary float get_health() const { return _health; } - // Set calibration speed: 0 - slowest, 4 - fastest - // On-Chip Calib manager will reduce speed if needed - void set_speed(int speed) { _speed = speed; } - // Write new calibration to the device void keep(); @@ -53,6 +49,7 @@ namespace rs2 int average_step_count = 20; int step_count = 20; int accuracy = 2; + int speed = 3; bool tare = false; void calibrate(); @@ -68,7 +65,6 @@ namespace rs2 void process_flow(std::function cleanup, invoker invoke) override; float _health = 0.f; - int _speed = 4; device _dev; bool _was_streaming = false; @@ -101,6 +97,7 @@ namespace rs2 RS2_CALIB_STATE_CALIB_IN_PROCESS,// Calibration in process... Shows progressbar RS2_CALIB_STATE_CALIB_COMPLETE, // Calibration complete, show before/after toggle and metrics RS2_CALIB_STATE_TARE_INPUT, // Collect input parameters for Tare calib + RS2_CALIB_STATE_SELF_INPUT, // Collect input parameters for Self calib }; autocalib_notification_model(std::string name, diff --git a/common/viewer.cpp b/common/viewer.cpp index ec6834a995..cee47a57d1 100644 --- a/common/viewer.cpp +++ b/common/viewer.cpp @@ -1684,11 +1684,7 @@ namespace rs2 ImGui::PushFont(window.get_large_font()); ImGui::PushStyleColor(ImGuiCol_Border, black); - int buttons = window.is_fullscreen() ? 5 : 4; - - ImGui::SetCursorPosX(window.width() - panel_width - panel_y * (buttons - 2)); - not_model.draw_snoozed_button(); - ImGui::SameLine(); + int buttons = window.is_fullscreen() ? 4 : 3; ImGui::SetCursorPosX(window.width() - panel_width - panel_y * (buttons)); ImGui::PushStyleColor(ImGuiCol_Text, is_3d_view ? light_grey : light_blue); @@ -1716,7 +1712,7 @@ namespace rs2 ImGui::PopStyleColor(2); ImGui::SameLine(); - ImGui::SetCursorPosX(window.width() - panel_width - panel_y * (buttons - 3)); + ImGui::SetCursorPosX(window.width() - panel_width - panel_y * (buttons - 2)); static bool settings_open = false; ImGui::PushStyleColor(ImGuiCol_Text, !settings_open ? light_grey : light_blue); From ba2f0071fac694895d9bc47768725e6e7d66d50f Mon Sep 17 00:00:00 2001 From: "Dorodnicov, Sergey" Date: Mon, 16 Sep 2019 05:12:24 -0700 Subject: [PATCH 3/4] Bump version --- include/librealsense2/rs.h | 2 +- package.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/include/librealsense2/rs.h b/include/librealsense2/rs.h index 461e2120c5..0b172c6949 100644 --- a/include/librealsense2/rs.h +++ b/include/librealsense2/rs.h @@ -24,7 +24,7 @@ extern "C" { #define RS2_API_MAJOR_VERSION 2 #define RS2_API_MINOR_VERSION 28 -#define RS2_API_PATCH_VERSION 0 +#define RS2_API_PATCH_VERSION 1 #define RS2_API_BUILD_VERSION 0 #ifndef STRINGIFY diff --git a/package.xml b/package.xml index 09e2eed6f5..6e42c46b83 100644 --- a/package.xml +++ b/package.xml @@ -7,7 +7,7 @@ librealsense2 - 2.28.0 + 2.28.1 Library for capturing data from the Intel(R) RealSense(TM) SR300, D400 Depth cameras and T2xx Tracking devices. This effort was initiated to better support researchers, creative coders, and app developers in domains such as robotics, virtual reality, and the internet of things. Several often-requested features of RealSense(TM); devices are implemented in this project. From ce53f6e9e19e1bb4d349f94ea0424e8f0fde6673 Mon Sep 17 00:00:00 2001 From: "Dorodnicov, Sergey" Date: Mon, 16 Sep 2019 05:31:59 -0700 Subject: [PATCH 4/4] Disable recommended version for the SR300 family --- common/fw-update-helper.cpp | 12 ++++++------ common/fw-update-helper.h | 2 +- common/model-views.cpp | 4 +--- src/ivcam/sr300.cpp | 4 ++-- 4 files changed, 10 insertions(+), 12 deletions(-) diff --git a/common/fw-update-helper.cpp b/common/fw-update-helper.cpp index f43a1fb7b2..d13e700c91 100644 --- a/common/fw-update-helper.cpp +++ b/common/fw-update-helper.cpp @@ -38,9 +38,11 @@ namespace rs2 RS2_FWU_STATE_FAILED = 3, }; - bool is_recommended_fw_available() + bool is_recommended_fw_available(std::string id) { - return !(strcmp("", FW_D4XX_FW_IMAGE_VERSION) == 0); + auto pl = parse_product_line(id); + auto fv = get_available_firmware_version(pl); + return !(fv == ""); } int parse_product_line(std::string id) @@ -56,8 +58,6 @@ namespace rs2 if (product_line == RS2_PRODUCT_LINE_D400 && allow_rc_firmware) return FW_D4XX_RC_IMAGE_VERSION; else if (product_line == RS2_PRODUCT_LINE_D400) return FW_D4XX_FW_IMAGE_VERSION; - // NOTE: For now removing recommended firmware version for SR30x series - // TODO: Re-enable in future release //else if (product_line == RS2_PRODUCT_LINE_SR300) return FW_SR3XX_FW_IMAGE_VERSION; else return ""; } @@ -439,7 +439,7 @@ namespace rs2 void fw_update_notification_model::draw_expanded(ux_window& win, std::string& error_message) { - if (update_manager->started() && update_state == RS2_FWU_STATE_INITIAL_PROMPT) + if (update_manager->started() && update_state == RS2_FWU_STATE_INITIAL_PROMPT) update_state = RS2_FWU_STATE_IN_PROGRESS; auto flags = ImGuiWindowFlags_NoResize | @@ -550,4 +550,4 @@ namespace rs2 pinned = true; } -} +} \ No newline at end of file diff --git a/common/fw-update-helper.h b/common/fw-update-helper.h index d5e0b06a60..e71f6c8081 100644 --- a/common/fw-update-helper.h +++ b/common/fw-update-helper.h @@ -12,7 +12,7 @@ namespace rs2 std::map> create_default_fw_table(); std::vector parse_fw_version(const std::string& fw); bool is_upgradeable(const std::string& curr, const std::string& available); - bool is_recommended_fw_available(); + bool is_recommended_fw_available(std::string version); class firmware_update_manager : public process_manager { diff --git a/common/model-views.cpp b/common/model-views.cpp index d42b68962f..71615ccfe3 100644 --- a/common/model-views.cpp +++ b/common/model-views.cpp @@ -4328,9 +4328,7 @@ namespace rs2 if (ImGui::IsItemHovered()) ImGui::SetTooltip("Install official signed firmware from file to the device"); - if (is_recommended_fw_available() && - ((dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE)) || - (dev.query_sensors().size() && dev.query_sensors().front().supports(RS2_CAMERA_INFO_PRODUCT_LINE)))) + if (dev.supports(RS2_CAMERA_INFO_PRODUCT_LINE) && is_recommended_fw_available(dev.get_info(RS2_CAMERA_INFO_PRODUCT_LINE))) { if (ImGui::Selectable("Install Recommended Firmware ")) { diff --git a/src/ivcam/sr300.cpp b/src/ivcam/sr300.cpp index 9a55c09a05..b1f2fddfd5 100644 --- a/src/ivcam/sr300.cpp +++ b/src/ivcam/sr300.cpp @@ -281,7 +281,7 @@ namespace librealsense enable_timestamp(true, true); auto pid_hex_str = hexify(color.pid); - auto recommended_fw_version = firmware_version(SR3XX_RECOMMENDED_FIRMWARE_VERSION); + //auto recommended_fw_version = firmware_version(SR3XX_RECOMMENDED_FIRMWARE_VERSION); register_info(RS2_CAMERA_INFO_NAME, device_name); register_info(RS2_CAMERA_INFO_SERIAL_NUMBER, serial); @@ -292,7 +292,7 @@ namespace librealsense register_info(RS2_CAMERA_INFO_PRODUCT_ID, pid_hex_str); register_info(RS2_CAMERA_INFO_PRODUCT_LINE, "SR300"); register_info(RS2_CAMERA_INFO_CAMERA_LOCKED, _is_locked ? "YES" : "NO"); - register_info(RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION, recommended_fw_version); + //register_info(RS2_CAMERA_INFO_RECOMMENDED_FIRMWARE_VERSION, recommended_fw_version); register_autorange_options();