From e21bdcc32e3778f97b91e1bee466e2681892670d Mon Sep 17 00:00:00 2001 From: remibettan Date: Tue, 5 May 2020 22:25:47 +0300 Subject: [PATCH 01/43] fw_logger class started --- src/fw_logger.cpp | 23 +++++++++++++++++++++++ src/fw_logger.h | 21 +++++++++++++++++++++ 2 files changed, 44 insertions(+) create mode 100644 src/fw_logger.cpp create mode 100644 src/fw_logger.h diff --git a/src/fw_logger.cpp b/src/fw_logger.cpp new file mode 100644 index 0000000000..efeb2a9808 --- /dev/null +++ b/src/fw_logger.cpp @@ -0,0 +1,23 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +#include "fw_logger.h" +#include + +namespace librealsense +{ + fw_logger::fw_logger(const char* camera_op_code) + { + auto op_code = static_cast(std::stoi(camera_op_code)); + _input_code = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, + 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + + } + + + std::vector fw_logger::get_fw_logs() const + { + return _debug_interface->send_receive_raw_data + } +} \ No newline at end of file diff --git a/src/fw_logger.h b/src/fw_logger.h new file mode 100644 index 0000000000..c0a5829de5 --- /dev/null +++ b/src/fw_logger.h @@ -0,0 +1,21 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +#pragma once + +#include + +namespace librealsense +{ + class fw_logger + { + public: + fw_logger(const char* camera_op_code); + + std::vector get_fw_logs() const; + + private: + std::vector _input_code; + }; + +} \ No newline at end of file From 783fd9adfa54486aa58755cf5da2436e1d41a789 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 6 May 2020 21:13:03 +0300 Subject: [PATCH 02/43] API and example added - FW logs received without any filter and without xml translation --- examples/CMakeLists.txt | 1 + examples/firmware-logs/CMakeLists.txt | 16 +++ examples/firmware-logs/rs-firmware-logs.cpp | 114 ++++++++++++++++++++ include/librealsense2/h/rs_device.h | 3 + include/librealsense2/h/rs_types.h | 1 + include/librealsense2/hpp/rs_device.hpp | 35 ++++++ include/librealsense2/rs.h | 7 ++ src/CMakeLists.txt | 2 + src/ds5/ds5-factory.cpp | 8 +- src/firmware_logger_device.cpp | 29 +++++ src/firmware_logger_device.h | 34 ++++++ src/fw_logger.cpp | 23 ---- src/fw_logger.h | 21 ---- src/realsense.def | 4 +- src/rs.cpp | 13 ++- src/types.cpp | 1 + 16 files changed, 264 insertions(+), 48 deletions(-) create mode 100644 examples/firmware-logs/CMakeLists.txt create mode 100644 examples/firmware-logs/rs-firmware-logs.cpp create mode 100644 src/firmware_logger_device.cpp create mode 100644 src/firmware_logger_device.h delete mode 100644 src/fw_logger.cpp delete mode 100644 src/fw_logger.h diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index cf04932166..c01d08be23 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -47,3 +47,4 @@ add_subdirectory(ar-basic) add_subdirectory(ar-advanced) add_subdirectory(pose-apriltag) add_subdirectory(tracking-and-depth) +add_subdirectory(firmware-logs) diff --git a/examples/firmware-logs/CMakeLists.txt b/examples/firmware-logs/CMakeLists.txt new file mode 100644 index 0000000000..929185ad15 --- /dev/null +++ b/examples/firmware-logs/CMakeLists.txt @@ -0,0 +1,16 @@ +# License: Apache 2.0. See LICENSE file in root directory. +# Copyright(c) 2020 Intel Corporation. All Rights Reserved. +# minimum required cmake version: 3.1.0 +cmake_minimum_required(VERSION 3.1.0) + +project(RealsenseExamplesFirmwareLogs) + +if(BUILD_GRAPHICAL_EXAMPLES) + add_executable(rs-firmware-logs rs-firmware-logs.cpp ../example.hpp) + set_property(TARGET rs-firmware-logs PROPERTY CXX_STANDARD 11) + target_link_libraries(rs-firmware-logs ${DEPENDENCIES}) + include_directories(rs-firmware-logs ../ ../../third-party/tclap/include) + set_target_properties (rs-firmware-logs PROPERTIES FOLDER "Examples") + + install(TARGETS rs-firmware-logs RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}) +endif() diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp new file mode 100644 index 0000000000..8f5265ba67 --- /dev/null +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -0,0 +1,114 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2017 Intel Corporation. All Rights Reserved. + +#include // Include RealSense Cross Platform API +#include "example.hpp" // Include short list of convenience functions for rendering +#include +#include +#include + +using namespace std; + + +string hexify(unsigned char n) +{ + string res; + + do + { + res += "0123456789ABCDEF"[n % 16]; + n >>= 4; + } while (n); + + reverse(res.begin(), res.end()); + + if (res.size() == 1) + { + res.insert(0, "0"); + } + + return res; +} + +string datetime_string() +{ + auto t = time(nullptr); + char buffer[20] = {}; + const tm* time = localtime(&t); + if (nullptr != time) + strftime(buffer, sizeof(buffer), "%Y-%m-%d %H:%M:%S", time); + + return string(buffer); +} + +// Capture Example demonstrates how to +// capture depth and color video streams and render them to the screen +int main(int argc, char * argv[]) +{ + // Declare RealSense pipeline, encapsulating the actual device and sensors + rs2::pipeline pipe; + + // Start streaming with default recommended configuration + // The default video configuration contains Depth and Color streams + // If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default + auto res = pipe.start(); + + rs2::context ctx; + rs2::device_hub hub(ctx); + while (true) + { + try + { + cout << "\nWaiting for RealSense device to connect...\n"; + auto dev = hub.wait_for_device(); + cout << "RealSense device was connected...\n"; + + setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout + + while (hub.is_connected(dev)) + { + this_thread::sleep_for(chrono::milliseconds(100)); + + auto fw_log = res.get_device().as(); + std::vector raw_data = fw_log.get_firmware_logs(); + vector fw_log_lines = { "" }; + if (raw_data.size() <= 4) + continue; + + /*if (use_xml_file) + { + fw_logs_binary_data fw_logs_binary_data = { raw_data }; + fw_logs_binary_data.logs_buffer.erase(fw_logs_binary_data.logs_buffer.begin(), fw_logs_binary_data.logs_buffer.begin() + 4); + fw_log_lines = fw_log_parser->get_fw_log_lines(fw_logs_binary_data); + for (auto& elem : fw_log_lines) + elem = datetime_string() + " " + elem; + } + else + { + stringstream sstr; + sstr << datetime_string() << " FW_Log_Data:"; + for (size_t i = 0; i < raw_data.size(); ++i) + sstr << hexify(raw_data[i]) << " "; + + fw_log_lines.push_back(sstr.str()); + }*/ + + stringstream sstr; + sstr << datetime_string() << " FW_Log_Data:"; + for (size_t i = 0; i < raw_data.size(); ++i) + sstr << hexify(raw_data[i]) << " "; + + fw_log_lines.push_back(sstr.str()); + + for (auto& line : fw_log_lines) + cout << line << endl; + } + } + catch (const rs2::error & e) + { + cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << endl; + } + } + + return EXIT_SUCCESS; +} diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index 43ba91b8d3..885fc6df9f 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -353,6 +353,9 @@ rs2_raw_data_buffer* rs2_serialize_json(rs2_device* dev, rs2_error** error); /* Load JSON and apply advanced-mode controls */ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error); +/* Get firmware Logs */ +const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error); + #ifdef __cplusplus } #endif diff --git a/include/librealsense2/h/rs_types.h b/include/librealsense2/h/rs_types.h index 02415278b3..ef4262013c 100644 --- a/include/librealsense2/h/rs_types.h +++ b/include/librealsense2/h/rs_types.h @@ -180,6 +180,7 @@ typedef enum rs2_extension RS2_EXTENSION_FISHEYE_SENSOR, RS2_EXTENSION_DEPTH_HUFFMAN_DECODER, RS2_EXTENSION_SERIALIZABLE, + RS2_EXTENSION_FW_LOGGER, RS2_EXTENSION_COUNT } rs2_extension; const char* rs2_extension_type_to_string(rs2_extension type); diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index 2ea37487a0..6ee943e893 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -312,6 +312,41 @@ return results; } }; + class firmware_logger : public device + { + public: + firmware_logger(device d) + : device(d.get()) + { + rs2_error* e = nullptr; + if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_FW_LOGGER, &e) == 0 && !e) + { + _dev.reset(); + } + error::handle(e); + } + + std::vector get_firmware_logs() const + { + std::vector results; + + rs2_error* e = nullptr; + std::shared_ptr list( + rs2_get_firmware_logs(_dev.get(), &e), + rs2_delete_raw_data); + error::handle(e); + + auto size = rs2_get_raw_data_size(list.get(), &e); + error::handle(e); + + auto start = rs2_get_raw_data(list.get(), &e); + + results.insert(results.begin(), start, start + size); + + return results; + } + }; + class auto_calibrated_device : public calibrated_device { public: diff --git a/include/librealsense2/rs.h b/include/librealsense2/rs.h index f43e816461..65fa5be7fe 100644 --- a/include/librealsense2/rs.h +++ b/include/librealsense2/rs.h @@ -110,6 +110,13 @@ float rs2_depth_frame_get_distance(const rs2_frame* frame_ref, int x, int y, rs2 */ rs2_time_t rs2_get_time( rs2_error** error); +/** + * Get Firmware logs + * \param[in] dev The Device + * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored + */ +const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error); + #ifdef __cplusplus } #endif diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index d26732bacf..f3022f6ba5 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -77,6 +77,7 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/device_hub.cpp" "${CMAKE_CURRENT_LIST_DIR}/environment.cpp" "${CMAKE_CURRENT_LIST_DIR}/error-handling.cpp" + "${CMAKE_CURRENT_LIST_DIR}/firmware_logger_device.cpp" "${CMAKE_CURRENT_LIST_DIR}/global_timestamp_reader.cpp" "${CMAKE_CURRENT_LIST_DIR}/hw-monitor.cpp" "${CMAKE_CURRENT_LIST_DIR}/image.cpp" @@ -105,6 +106,7 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/environment.h" "${CMAKE_CURRENT_LIST_DIR}/log.h" "${CMAKE_CURRENT_LIST_DIR}/error-handling.h" + "${CMAKE_CURRENT_LIST_DIR}/firmware_logger_device.h" "${CMAKE_CURRENT_LIST_DIR}/frame-archive.h" "${CMAKE_CURRENT_LIST_DIR}/global_timestamp_reader.h" "${CMAKE_CURRENT_LIST_DIR}/hw-monitor.h" diff --git a/src/ds5/ds5-factory.cpp b/src/ds5/ds5-factory.cpp index f039dc429d..1923da4ede 100644 --- a/src/ds5/ds5-factory.cpp +++ b/src/ds5/ds5-factory.cpp @@ -22,6 +22,8 @@ #include "ds5-motion.h" #include "sync.h" +#include "../firmware_logger_device.h" + namespace librealsense { // PSR @@ -471,7 +473,8 @@ namespace librealsense // AWGC class rs435_device : public ds5_active, public ds5_color, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs435_device(std::shared_ptr ctx, @@ -481,7 +484,8 @@ namespace librealsense ds5_device(ctx, group), ds5_active(ctx, group), ds5_color(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor().get_info(RS2_CAMERA_INFO_DEBUG_OP_CODE)) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp new file mode 100644 index 0000000000..970c567a95 --- /dev/null +++ b/src/firmware_logger_device.cpp @@ -0,0 +1,29 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +#include "firmware_logger_device.h" +#include + +namespace librealsense +{ + firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, + std::string camera_op_code) : + _hw_monitor(hardware_monitor) + { + auto op_code = static_cast(std::stoi(camera_op_code.c_str())); + _input_code = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, + 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + } + + + std::vector firmware_logger_device::get_fw_logs() const + { + auto res = _hw_monitor->send(_input_code); + if (res.empty()) + { + throw std::runtime_error("Getting Firmware logs failed!"); + } + return res; + } +} \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h new file mode 100644 index 0000000000..4456988a98 --- /dev/null +++ b/src/firmware_logger_device.h @@ -0,0 +1,34 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +#pragma once + +#include "core/extension.h" +#include "device.h" +#include + +namespace librealsense +{ + class firmware_logger_extensions + { + public: + virtual std::vector get_fw_logs() const = 0; + virtual ~firmware_logger_extensions() = default; + }; + MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); + + + class firmware_logger_device : public virtual device, public firmware_logger_extensions + { + public: + firmware_logger_device(std::shared_ptr hardware_monitor, + std::string camera_op_code); + + std::vector get_fw_logs() const override; + + private: + std::vector _input_code; + std::shared_ptr _hw_monitor; + }; + +} \ No newline at end of file diff --git a/src/fw_logger.cpp b/src/fw_logger.cpp deleted file mode 100644 index efeb2a9808..0000000000 --- a/src/fw_logger.cpp +++ /dev/null @@ -1,23 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2020 Intel Corporation. All Rights Reserved. - -#include "fw_logger.h" -#include - -namespace librealsense -{ - fw_logger::fw_logger(const char* camera_op_code) - { - auto op_code = static_cast(std::stoi(camera_op_code)); - _input_code = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, - 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; - - } - - - std::vector fw_logger::get_fw_logs() const - { - return _debug_interface->send_receive_raw_data - } -} \ No newline at end of file diff --git a/src/fw_logger.h b/src/fw_logger.h deleted file mode 100644 index c0a5829de5..0000000000 --- a/src/fw_logger.h +++ /dev/null @@ -1,21 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2020 Intel Corporation. All Rights Reserved. - -#pragma once - -#include - -namespace librealsense -{ - class fw_logger - { - public: - fw_logger(const char* camera_op_code); - - std::vector get_fw_logs() const; - - private: - std::vector _input_code; - }; - -} \ No newline at end of file diff --git a/src/realsense.def b/src/realsense.def index c7fcea8299..e0bdd94163 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -355,7 +355,9 @@ EXPORTS rs2_run_tare_calibration rs2_get_calibration_table rs2_set_calibration_table - + + rs2_get_firmware_logs + rs2_create_terminal_parser rs2_delete_terminal_parser rs2_terminal_parse_command diff --git a/src/rs.cpp b/src/rs.cpp index 9e3e2a9d27..4fd4942e2a 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -42,6 +42,7 @@ #include "global_timestamp_reader.h" #include "auto-calibrated-device.h" #include "terminal-parser.h" +#include "firmware_logger_device.h" //////////////////////// // API implementation // //////////////////////// @@ -1292,6 +1293,7 @@ int rs2_is_device_extendable_to(const rs2_device* dev, rs2_extension extension, case RS2_EXTENSION_GLOBAL_TIMER : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::global_time_interface) != nullptr; case RS2_EXTENSION_AUTO_CALIBRATED_DEVICE: return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::auto_calibrated_interface) != nullptr; case RS2_EXTENSION_SERIALIZABLE : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::serializable_interface) != nullptr; + case RS2_EXTENSION_FW_LOGGER : return VALIDATE_INTERFACE_NO_THROW(dev->device, librealsense::firmware_logger_extensions) != nullptr; default: return false; @@ -2969,6 +2971,16 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s } HANDLE_EXCEPTIONS_AND_RETURN(, dev, json_content, content_size) +const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(dev); + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + + std::vector buffer = fw_loggerable->get_fw_logs(); + return new rs2_raw_data_buffer{ buffer }; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev) + rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_content); @@ -3019,4 +3031,3 @@ rs2_raw_data_buffer* rs2_terminal_parse_response(rs2_terminal_parser* terminal_p return new rs2_raw_data_buffer{ result }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, terminal_parser, command, response) - diff --git a/src/types.cpp b/src/types.cpp index 7d03962288..fa56fde3f2 100644 --- a/src/types.cpp +++ b/src/types.cpp @@ -216,6 +216,7 @@ namespace librealsense CASE(FISHEYE_SENSOR) CASE(DEPTH_HUFFMAN_DECODER) CASE(SERIALIZABLE) + CASE(FW_LOGGER) default: assert(!is_valid(value)); return UNKNOWN_VALUE; } #undef CASE From 39326f0681cf332b06031e86d4344eb659775f8b Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 13 May 2020 12:30:46 +0300 Subject: [PATCH 03/43] FW logs parsed, using new line as delimiter --- examples/firmware-logs/rs-firmware-logs.cpp | 38 ++- include/librealsense2/h/rs_device.h | 25 ++ include/librealsense2/h/rs_types.h | 1 + include/librealsense2/hpp/rs_device.hpp | 55 +++- src/CMakeLists.txt | 1 + src/fw-logs-parser/CMakeLists.txt | 14 + src/fw-logs-parser/fw-log-data.cpp | 60 ++++ src/fw-logs-parser/fw-log-data.h | 94 ++++++ .../fw-logs-formating-options.cpp | 95 ++++++ .../fw-logs-formating-options.h | 54 +++ src/fw-logs-parser/fw-logs-parser.cpp | 103 ++++++ src/fw-logs-parser/fw-logs-parser.h | 30 ++ src/fw-logs-parser/fw-logs-xml-helper.cpp | 311 ++++++++++++++++++ src/fw-logs-parser/fw-logs-xml-helper.h | 48 +++ src/fw-logs-parser/fw-string-formatter.cpp | 138 ++++++++ src/fw-logs-parser/fw-string-formatter.h | 28 ++ src/realsense.def | 3 + src/rs.cpp | 50 +++ 18 files changed, 1131 insertions(+), 17 deletions(-) create mode 100644 src/fw-logs-parser/CMakeLists.txt create mode 100644 src/fw-logs-parser/fw-log-data.cpp create mode 100644 src/fw-logs-parser/fw-log-data.h create mode 100644 src/fw-logs-parser/fw-logs-formating-options.cpp create mode 100644 src/fw-logs-parser/fw-logs-formating-options.h create mode 100644 src/fw-logs-parser/fw-logs-parser.cpp create mode 100644 src/fw-logs-parser/fw-logs-parser.h create mode 100644 src/fw-logs-parser/fw-logs-xml-helper.cpp create mode 100644 src/fw-logs-parser/fw-logs-xml-helper.h create mode 100644 src/fw-logs-parser/fw-string-formatter.cpp create mode 100644 src/fw-logs-parser/fw-string-formatter.h diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index 8f5265ba67..40c0ac3765 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -6,6 +6,7 @@ #include #include #include +#include using namespace std; @@ -68,20 +69,32 @@ int main(int argc, char * argv[]) while (hub.is_connected(dev)) { this_thread::sleep_for(chrono::milliseconds(100)); - + auto fw_log = res.get_device().as(); std::vector raw_data = fw_log.get_firmware_logs(); vector fw_log_lines = { "" }; if (raw_data.size() <= 4) continue; - /*if (use_xml_file) + static bool usingParser = true; + if (usingParser) { - fw_logs_binary_data fw_logs_binary_data = { raw_data }; - fw_logs_binary_data.logs_buffer.erase(fw_logs_binary_data.logs_buffer.begin(), fw_logs_binary_data.logs_buffer.begin() + 4); - fw_log_lines = fw_log_parser->get_fw_log_lines(fw_logs_binary_data); - for (auto& elem : fw_log_lines) - elem = datetime_string() + " " + elem; + std::string xml_path("HWLoggerEventsDS5.xml"); + if (!xml_path.empty()) + { + ifstream f(xml_path); + if (f.good()) + { + unique_ptr parser = + unique_ptr(new rs2::firmware_logs_parser(xml_path)); + bool datetime = true; + fw_log_lines = parser->get_firmware_logs_parsed(raw_data); + + for (auto& elem : fw_log_lines) + elem = datetime_string() + " " + elem; + } + } + } else { @@ -91,15 +104,8 @@ int main(int argc, char * argv[]) sstr << hexify(raw_data[i]) << " "; fw_log_lines.push_back(sstr.str()); - }*/ - - stringstream sstr; - sstr << datetime_string() << " FW_Log_Data:"; - for (size_t i = 0; i < raw_data.size(); ++i) - sstr << hexify(raw_data[i]) << " "; - - fw_log_lines.push_back(sstr.str()); - + } + for (auto& line : fw_log_lines) cout << line << endl; } diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index 885fc6df9f..31903d5905 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -356,6 +356,31 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s /* Get firmware Logs */ const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error); +/** +* \brief Creates RealSense firmware logs parser. +* \param[in] xml_path path to xml file needed for parsing +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return firmware logs parser object +*/ +rs2_firmware_logs_parser* rs2_create_firmware_logs_parser(const char* xml_path, rs2_error** error); + +/** +* \brief Frees the relevant firmware logs parser object. +* \param[in] firmware logs parser object that is no longer needed +*/ +void rs2_delete_firmware_logs_parser(rs2_firmware_logs_parser* parser); + +/** +* \brief Parses firmware logs. +* \param[in] fw_logs_parser firmware logs parser object +* \param[in] raw_data firmware logs not parsed +* \param[in] raw_data_size firmware logs not parsed size +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return firmware logs parsed +*/ +rs2_raw_data_buffer* rs2_get_firmware_logs_parsed(rs2_firmware_logs_parser* fw_logs_parser, + const void* raw_data, const int raw_data_size, rs2_error** error); + #ifdef __cplusplus } #endif diff --git a/include/librealsense2/h/rs_types.h b/include/librealsense2/h/rs_types.h index ef4262013c..8c9d01c96f 100644 --- a/include/librealsense2/h/rs_types.h +++ b/include/librealsense2/h/rs_types.h @@ -253,6 +253,7 @@ typedef void (*rs2_devices_changed_callback_ptr)(rs2_device_list*, rs2_device_li typedef void (*rs2_frame_callback_ptr)(rs2_frame*, void*); typedef void (*rs2_frame_processor_callback_ptr)(rs2_frame*, rs2_source*, void*); typedef void(*rs2_update_progress_callback_ptr)(const float, void*); +typedef struct rs2_firmware_logs_parser rs2_firmware_logs_parser; typedef double rs2_time_t; /**< Timestamp format. units are milliseconds */ typedef long long rs2_metadata_type; /**< Metadata attribute type is defined as 64 bit signed integer*/ diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index 6ee943e893..27421d2958 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -226,7 +226,7 @@ namespace rs2 results.insert(results.begin(), start, start + size); -return results; + return results; } // Update an updatable device to the provided unsigned firmware. This call is executed on the caller's thread. @@ -347,6 +347,59 @@ return results; } }; + class firmware_logs_parser + { + public: + firmware_logs_parser(std::string xml_path) + { + rs2_error* e = nullptr; + _firmware_logs_parser = std::shared_ptr( + rs2_create_firmware_logs_parser(xml_path.data(), &e), + rs2_delete_firmware_logs_parser); + error::handle(e); + } + + std::vector firmware_logs_parser::get_firmware_logs_parsed(const std::vector& raw_data) + { + std::string results; + + rs2_error* e = nullptr; + std::shared_ptr parsed_logs( + rs2_get_firmware_logs_parsed(_firmware_logs_parser.get(), (const void*)raw_data.data(), (const int)raw_data.size(), &e), + rs2_delete_raw_data); + rs2::error::handle(e); + + auto size = rs2_get_raw_data_size(parsed_logs.get(), &e); + rs2::error::handle(e); + + auto start = rs2_get_raw_data(parsed_logs.get(), &e); + rs2::error::handle(e); + + results.insert(results.begin(), start, start + size); + + //transforming the string to vector delimiter is '\n' + std::vector log_lines; + std::size_t current_start = 0; + std::size_t delimiter_found = results.find_first_of("\n"); + while (delimiter_found != std::string::npos) + { + log_lines.push_back(std::string(results.substr(current_start, delimiter_found - current_start))); + current_start = delimiter_found + 1; + delimiter_found = results.find_first_of("\n", delimiter_found + 1); + } + + return log_lines; + } + + firmware_logs_parser(std::shared_ptr fw_logs_parser) + : _firmware_logs_parser(fw_logs_parser) {} + + explicit operator std::shared_ptr() { return _firmware_logs_parser; }; + + protected: + std::shared_ptr _firmware_logs_parser; + }; + class auto_calibrated_device : public calibrated_device { public: diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index f3022f6ba5..9052efa050 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -11,6 +11,7 @@ include(${_rel_path}/proc/CMakeLists.txt) include(${_rel_path}/res/CMakeLists.txt) include(${_rel_path}/pipeline/CMakeLists.txt) include(${_rel_path}/usb/CMakeLists.txt) +include(${_rel_path}/fw-logs-parser/CMakeLists.txt) include(${_rel_path}/fw-update/CMakeLists.txt) message(STATUS "using ${BACKEND}") diff --git a/src/fw-logs-parser/CMakeLists.txt b/src/fw-logs-parser/CMakeLists.txt new file mode 100644 index 0000000000..33f79d0b81 --- /dev/null +++ b/src/fw-logs-parser/CMakeLists.txt @@ -0,0 +1,14 @@ +# License: Apache 2.0. See LICENSE file in root directory. +# Copyright(c) 2020 Intel Corporation. All Rights Reserved. +target_sources(${LRS_TARGET} + PRIVATE + "${CMAKE_CURRENT_LIST_DIR}/fw-log-data.h" + "${CMAKE_CURRENT_LIST_DIR}/fw-logs-formating-options.cpp" + "${CMAKE_CURRENT_LIST_DIR}/fw-logs-formating-options.h" + "${CMAKE_CURRENT_LIST_DIR}/fw-logs-parser.cpp" + "${CMAKE_CURRENT_LIST_DIR}/fw-logs-parser.h" + "${CMAKE_CURRENT_LIST_DIR}/fw-logs-xml-helper.cpp" + "${CMAKE_CURRENT_LIST_DIR}/fw-logs-xml-helper.h" + "${CMAKE_CURRENT_LIST_DIR}/fw-string-formatter.cpp" + "${CMAKE_CURRENT_LIST_DIR}/fw-string-formatter.h" +) diff --git a/src/fw-logs-parser/fw-log-data.cpp b/src/fw-logs-parser/fw-log-data.cpp new file mode 100644 index 0000000000..50d3d4860f --- /dev/null +++ b/src/fw-logs-parser/fw-log-data.cpp @@ -0,0 +1,60 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2019 Intel Corporation. All Rights Reserved. +#include "fw-log-data.h" +#include +#include +#include +#include + +using namespace std; + +# define SET_WIDTH_AND_FILL(num, element) \ +setfill(' ') << setw(num) << left << element \ + +namespace librealsense +{ + namespace fw_logs_parsing + { + fw_log_data::fw_log_data(void) + { + magic_number = 0; + severity = 0; + file_id = 0; + group_id = 0; + event_id = 0; + line = 0; + sequence = 0; + p1 = 0; + p2 = 0; + p3 = 0; + timestamp = 0; + delta = 0; + message = ""; + file_name = ""; + } + + + fw_log_data::~fw_log_data(void) + { + } + + + string fw_log_data::to_string() + { + stringstream fmt; + + fmt << SET_WIDTH_AND_FILL(6, sequence) + << SET_WIDTH_AND_FILL(30, file_name) + << SET_WIDTH_AND_FILL(6, group_id) + << SET_WIDTH_AND_FILL(15, thread_name) + << SET_WIDTH_AND_FILL(6, severity) + << SET_WIDTH_AND_FILL(6, line) + << SET_WIDTH_AND_FILL(15, timestamp) + << SET_WIDTH_AND_FILL(15, delta) + << SET_WIDTH_AND_FILL(30, message); + + auto str = fmt.str(); + return str; + } + } +} diff --git a/src/fw-logs-parser/fw-log-data.h b/src/fw-logs-parser/fw-log-data.h new file mode 100644 index 0000000000..606d680894 --- /dev/null +++ b/src/fw-logs-parser/fw-log-data.h @@ -0,0 +1,94 @@ +/* License: Apache 2.0. See LICENSE file in root directory. */ +/* Copyright(c) 2019 Intel Corporation. All Rights Reserved. */ +#pragma once +#include +#include +#include + + +namespace librealsense +{ + namespace fw_logs_parsing + { + struct fw_logs_binary_data + { + std::vector logs_buffer; + }; + + typedef union + { + uint32_t value; + struct + { + uint32_t magic_number : 8; + uint32_t severity : 5; + uint32_t thread_id : 3; + uint32_t file_id : 11; + uint32_t group_id : 5; + } bits; + } fw_log_header_dword1; + + typedef union + { + uint32_t value; + struct + { + uint32_t event_id : 16; + uint32_t line_id : 12; + uint32_t seq_id : 4; + } bits; + } fw_log_header_dword2; + + struct fw_log_header_dword3 + { + uint16_t p1; + uint16_t p2; + }; + + struct fw_log_header_dword4 + { + uint32_t p3; + }; + + struct fw_log_header_dword5 + { + uint32_t timestamp; + }; + + struct fw_log_binary + { + fw_log_header_dword1 dword1; + fw_log_header_dword2 dword2; + fw_log_header_dword3 dword3; + fw_log_header_dword4 dword4; + fw_log_header_dword5 dword5; + }; + + + class fw_log_data + { + public: + fw_log_data(void); + ~fw_log_data(void); + + uint32_t magic_number; + uint32_t severity; + uint32_t file_id; + uint32_t group_id; + uint32_t event_id; + uint32_t line; + uint32_t sequence; + uint32_t p1; + uint32_t p2; + uint32_t p3; + uint64_t timestamp; + double delta; + + std::string message; + std::string file_name; + std::string thread_name; + + std::string to_string(); + }; + } +} diff --git a/src/fw-logs-parser/fw-logs-formating-options.cpp b/src/fw-logs-parser/fw-logs-formating-options.cpp new file mode 100644 index 0000000000..43e30acf61 --- /dev/null +++ b/src/fw-logs-parser/fw-logs-formating-options.cpp @@ -0,0 +1,95 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2019 Intel Corporation. All Rights Reserved. +#include "fw-logs-formating-options.h" +#include "fw-logs-xml-helper.h" +#include + + +using namespace std; +namespace librealsense +{ + namespace fw_logs_parsing + { + fw_log_event::fw_log_event() + : num_of_params(0), + line("") + {} + + fw_log_event::fw_log_event(int input_num_of_params, const string& input_line) + : num_of_params(input_num_of_params), + line(input_line) + {} + + + fw_logs_formating_options::fw_logs_formating_options(const string& xml_full_file_path) + : _xml_full_file_path(xml_full_file_path) + {} + + + fw_logs_formating_options::~fw_logs_formating_options(void) + { + } + + bool fw_logs_formating_options::get_event_data(int id, fw_log_event* log_event_data) const + { + auto event_it = _fw_logs_event_list.find(id); + if (event_it != _fw_logs_event_list.end()) + { + *log_event_data = event_it->second; + return true; + } + else + { + stringstream ss; + ss << "*** Unrecognized Log Id: "; + ss << id; + ss << "! P1 = 0x{0:x}, P2 = 0x{1:x}, P3 = 0x{2:x}"; + log_event_data->line = ss.str(); + log_event_data->num_of_params = 3; + return false; + } + } + + bool fw_logs_formating_options::get_file_name(int id, string* file_name) const + { + auto file_it = _fw_logs_file_names_list.find(id); + if (file_it != _fw_logs_file_names_list.end()) + { + *file_name = file_it->second; + return true; + } + else + { + *file_name = "Unknown"; + return false; + } + } + + bool fw_logs_formating_options::get_thread_name(uint32_t thread_id, string* thread_name) const + { + auto file_it = _fw_logs_thread_names_list.find(thread_id); + if (file_it != _fw_logs_thread_names_list.end()) + { + *thread_name = file_it->second; + return true; + } + else + { + *thread_name = "Unknown"; + return false; + } + } + + std::unordered_map> fw_logs_formating_options::get_enums() const + { + return _fw_logs_enum_names_list; + } + + bool fw_logs_formating_options::initialize_from_xml() + { + fw_logs_xml_helper fw_logs_xml(_xml_full_file_path); + return fw_logs_xml.build_log_meta_data(this); + } + } +} + diff --git a/src/fw-logs-parser/fw-logs-formating-options.h b/src/fw-logs-parser/fw-logs-formating-options.h new file mode 100644 index 0000000000..f67a198c95 --- /dev/null +++ b/src/fw-logs-parser/fw-logs-formating-options.h @@ -0,0 +1,54 @@ +/* License: Apache 2.0. See LICENSE file in root directory. */ +/* Copyright(c) 2019 Intel Corporation. All Rights Reserved. */ +#pragma once +#include +#include +#include +#include + +#ifdef ANDROID +#include "../../common/android_helpers.h" +#endif + + +namespace librealsense +{ + namespace fw_logs_parsing + { + struct fw_log_event + { + size_t num_of_params; + std::string line; + + fw_log_event(); + fw_log_event(int input_num_of_params, const std::string& input_line); + }; + + typedef std::pair kvp; // XML key/value pair + + class fw_logs_xml_helper; + + class fw_logs_formating_options + { + public: + fw_logs_formating_options(const std::string& xml_full_file_path); + ~fw_logs_formating_options(void); + + + bool get_event_data(int id, fw_log_event* log_event_data) const; + bool get_file_name(int id, std::string* file_name) const; + bool get_thread_name(uint32_t thread_id, std::string* thread_name) const; + std::unordered_map> get_enums() const; + bool initialize_from_xml(); + + private: + friend fw_logs_xml_helper; + std::unordered_map _fw_logs_event_list; + std::unordered_map _fw_logs_file_names_list; + std::unordered_map _fw_logs_thread_names_list; + std::unordered_map>> _fw_logs_enum_names_list; + + std::string _xml_full_file_path; + }; + } +} diff --git a/src/fw-logs-parser/fw-logs-parser.cpp b/src/fw-logs-parser/fw-logs-parser.cpp new file mode 100644 index 0000000000..37c1827cdf --- /dev/null +++ b/src/fw-logs-parser/fw-logs-parser.cpp @@ -0,0 +1,103 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2019 Intel Corporation. All Rights Reserved. +#include "fw-logs-parser.h" +#include +#include +#include "fw-string-formatter.h" +#include "stdint.h" + +using namespace std; + +namespace librealsense +{ + namespace fw_logs_parsing + { + fw_logs_parser::fw_logs_parser(string xml_full_file_path) + : _fw_logs_formating_options(xml_full_file_path), + _last_timestamp(0), + _timestamp_factor(0.00001) + { + _fw_logs_formating_options.initialize_from_xml(); + } + + + fw_logs_parser::~fw_logs_parser(void) + { + } + + vector fw_logs_parser::get_fw_log_lines(const fw_logs_binary_data& fw_logs_data_binary) + { + fw_logs_binary_data binary_data = { fw_logs_data_binary }; + binary_data.logs_buffer.erase(binary_data.logs_buffer.begin(), binary_data.logs_buffer.begin() + 4); + vector string_vector; + int num_of_lines = int(binary_data.logs_buffer.size()) / sizeof(fw_log_binary); + auto temp_pointer = reinterpret_cast(binary_data.logs_buffer.data()); + + for (int i = 0; i < num_of_lines; i++) + { + string line; + auto log = const_cast(reinterpret_cast(temp_pointer)); + line = generate_log_line(log); + string_vector.push_back(line); + temp_pointer++; + } + return string_vector; + } + + string fw_logs_parser::generate_log_line(char* fw_logs) + { + fw_log_data log_data; + fill_log_data(fw_logs, &log_data); + + return log_data.to_string(); + } + + void fw_logs_parser::fill_log_data(const char* fw_logs, fw_log_data* log_data) + { + fw_string_formatter reg_exp(_fw_logs_formating_options.get_enums()); + fw_log_event log_event_data; + + auto* log_binary = reinterpret_cast(fw_logs); + + //parse first DWORD + log_data->magic_number = static_cast(log_binary->dword1.bits.magic_number); + log_data->severity = static_cast(log_binary->dword1.bits.severity); + + log_data->file_id = static_cast(log_binary->dword1.bits.file_id); + log_data->group_id = static_cast(log_binary->dword1.bits.group_id); + + //parse second DWORD + log_data->event_id = static_cast(log_binary->dword2.bits.event_id); + log_data->line = static_cast(log_binary->dword2.bits.line_id); + log_data->sequence = static_cast(log_binary->dword2.bits.seq_id); + + //parse third DWORD + log_data->p1 = static_cast(log_binary->dword3.p1); + log_data->p2 = static_cast(log_binary->dword3.p2); + + //parse forth DWORD + log_data->p3 = static_cast(log_binary->dword4.p3); + + //parse fifth DWORD + log_data->timestamp = log_binary->dword5.timestamp; + + if (_last_timestamp == 0) + { + log_data->delta = 0; + } + else + { + log_data->delta = (log_data->timestamp - _last_timestamp) * _timestamp_factor; + } + + _last_timestamp = log_data->timestamp; + _fw_logs_formating_options.get_event_data(log_data->event_id, &log_event_data); + uint32_t params[3] = { log_data->p1, log_data->p2, log_data->p3 }; + reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &log_data->message); + + _fw_logs_formating_options.get_file_name(log_data->file_id, &log_data->file_name); + _fw_logs_formating_options.get_thread_name(static_cast(log_binary->dword1.bits.thread_id), + &log_data->thread_name); + } + } +} diff --git a/src/fw-logs-parser/fw-logs-parser.h b/src/fw-logs-parser/fw-logs-parser.h new file mode 100644 index 0000000000..7ed135558b --- /dev/null +++ b/src/fw-logs-parser/fw-logs-parser.h @@ -0,0 +1,30 @@ +/* License: Apache 2.0. See LICENSE file in root directory. */ +/* Copyright(c) 2019 Intel Corporation. All Rights Reserved. */ +#pragma once +#include +#include +#include +#include "fw-logs-formating-options.h" +#include "fw-log-data.h" + +namespace librealsense +{ + namespace fw_logs_parsing + { + class fw_logs_parser : public std::enable_shared_from_this + { + public: + explicit fw_logs_parser(std::string xml_full_file_path); + ~fw_logs_parser(void); + std::vector get_fw_log_lines(const fw_logs_binary_data& fw_logs_data_binary); + + private: + std::string generate_log_line(char* fw_logs); + void fill_log_data(const char* fw_logs, fw_log_data* log_data); + uint64_t _last_timestamp; + + fw_logs_formating_options _fw_logs_formating_options; + const double _timestamp_factor; + }; + } +} diff --git a/src/fw-logs-parser/fw-logs-xml-helper.cpp b/src/fw-logs-parser/fw-logs-xml-helper.cpp new file mode 100644 index 0000000000..a17e1b05e1 --- /dev/null +++ b/src/fw-logs-parser/fw-logs-xml-helper.cpp @@ -0,0 +1,311 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2019 Intel Corporation. All Rights Reserved. +#include "fw-logs-xml-helper.h" +#include +#include +#include +#include + +using namespace std; + +namespace librealsense +{ + namespace fw_logs_parsing + { + fw_logs_xml_helper::fw_logs_xml_helper(string xml_full_file_path) + : _init_done(false), + _xml_full_file_path(xml_full_file_path) + {} + + + fw_logs_xml_helper::~fw_logs_xml_helper(void) + { + // TODO: Add cleanup code + } + + bool fw_logs_xml_helper::get_root_node(xml_node<>** node) + { + if (_init_done) + { + *node = _xml_doc.first_node(); + return true; + } + + return false; + } + + bool fw_logs_xml_helper::try_load_external_xml() + { + try + { + if (_xml_full_file_path.empty()) + return false; + + rapidxml::file<> xml_file(_xml_full_file_path.c_str()); + + _document_buffer.resize(xml_file.size() + 2); + memcpy(_document_buffer.data(), xml_file.data(), xml_file.size()); + _document_buffer[xml_file.size()] = '\0'; + _document_buffer[xml_file.size() + 1] = '\0'; + _xml_doc.parse<0>(_document_buffer.data()); + + return true; + } + catch (...) + { + _document_buffer.clear(); + throw; + } + + return false; + } + + bool fw_logs_xml_helper::init() + { + _init_done = try_load_external_xml(); + return _init_done; + } + + bool fw_logs_xml_helper::build_log_meta_data(fw_logs_formating_options* log_meta_data) + { + xml_node<>* xml_root_node_list; + + if (!init()) + return false; + + if (!get_root_node(&xml_root_node_list)) + { + return false; + } + + string root_name(xml_root_node_list->name(), xml_root_node_list->name() + xml_root_node_list->name_size()); + + // check if Format is the first root name. + if (root_name.compare("Format") != 0) + return false; + + xml_node<>* events_node = xml_root_node_list->first_node(); + + + if (!build_meta_data_structure(events_node, log_meta_data)) + return false; + + return true; + } + + + bool fw_logs_xml_helper::build_meta_data_structure(xml_node<>* xml_node_list_of_events, fw_logs_formating_options* logs_formating_options) + { + node_type res = none; + int id{}; + int num_of_params{}; + string line; + + // loop through all elements in the Format. + for (xml_node<>* node = xml_node_list_of_events; node; node = node->next_sibling()) + { + line.clear(); + res = get_next_node(node, &id, &num_of_params, &line); + if (res == event) + { + fw_log_event log_event(num_of_params, line); + logs_formating_options->_fw_logs_event_list.insert(pair(id, log_event)); + } + else if (res == file) + { + logs_formating_options->_fw_logs_file_names_list.insert(kvp(id, line)); + } + else if (res == thread) + { + logs_formating_options->_fw_logs_thread_names_list.insert(kvp(id, line)); + } + else if (res == enums) + { + for (xml_node<>* enum_node = node->first_node(); enum_node; enum_node = enum_node->next_sibling()) + { + for (xml_attribute<>* attribute = enum_node->first_attribute(); attribute; attribute = attribute->next_attribute()) + { + string attr(attribute->name(), attribute->name() + attribute->name_size()); + if (attr.compare("Name") == 0) + { + string name_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + vector xml_kvp; + + for (xml_node<>* enum_value_node = enum_node->first_node(); enum_value_node; enum_value_node = enum_value_node->next_sibling()) + { + int key = 0; + string value_str; + for (xml_attribute<>* attribute = enum_value_node->first_attribute(); attribute; attribute = attribute->next_attribute()) + { + string attr(attribute->name(), attribute->name() + attribute->name_size()); + if (attr.compare("Value") == 0) + { + value_str = std::string(attribute->value(), attribute->value() + attribute->value_size()); + } + if (attr.compare("Key") == 0) + { + try + { + auto key_str = std::string(attribute->value()); + key = std::stoi(key_str, nullptr); + } + catch (...) {} + } + } + xml_kvp.push_back(std::make_pair(key, value_str)); + } + logs_formating_options->_fw_logs_enum_names_list.insert(pair>(name_attr_str, xml_kvp)); + } + } + } + } + else + return false; + } + + return true; + } + + fw_logs_xml_helper::node_type fw_logs_xml_helper::get_next_node(xml_node<>* node, int* id, int* num_of_params, string* line) + { + + string tag(node->name(), node->name() + node->name_size()); + + if (tag.compare("Event") == 0) + { + if (get_event_node(node, id, num_of_params, line)) + return event; + } + else if (tag.compare("File") == 0) + { + if (get_file_node(node, id, line)) + return file; + } + else if (tag.compare("Thread") == 0) + { + if (get_thread_node(node, id, line)) + return thread; + } + else if (tag.compare("Enums") == 0) + { + return enums; + } + return none; + } + + bool fw_logs_xml_helper::get_enum_name_node(xml_node<>* node_file, int* thread_id, string* enum_name) + { + for (xml_attribute<>* attribute = node_file->first_attribute(); attribute; attribute = attribute->next_attribute()) + { + string attr(attribute->name(), attribute->name() + attribute->name_size()); + + if (attr.compare("Name") == 0) + { + string name_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *enum_name = name_attr_str; + continue; + } + else + return false; + } + + return true; + } + bool fw_logs_xml_helper::get_enum_value_node(xml_node<>* node_file, int* thread_id, string* enum_name) + { + for (xml_attribute<>* attribute = node_file->first_attribute(); attribute; attribute = attribute->next_attribute()) + { + string attr(attribute->name(), attribute->name() + attribute->name_size()); + + if (attr.compare("Value") == 0) + { + string name_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *enum_name = name_attr_str; + continue; + } + else + return false; + } + + return true; + } + bool fw_logs_xml_helper::get_thread_node(xml_node<>* node_file, int* thread_id, string* thread_name) + { + for (xml_attribute<>* attribute = node_file->first_attribute(); attribute; attribute = attribute->next_attribute()) + { + string attr(attribute->name(), attribute->name() + attribute->name_size()); + + if (attr.compare("id") == 0) + { + string id_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *thread_id = stoi(id_attr_str); + continue; + } + else if (attr.compare("Name") == 0) + { + string name_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *thread_name = name_attr_str; + continue; + } + else + return false; + } + + return true; + } + + bool fw_logs_xml_helper::get_file_node(xml_node<>* node_file, int* file_id, string* file_name) + { + for (xml_attribute<>* attribute = node_file->first_attribute(); attribute; attribute = attribute->next_attribute()) + { + string attr(attribute->name(), attribute->name() + attribute->name_size()); + + if (attr.compare("id") == 0) + { + string id_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *file_id = stoi(id_attr_str); + continue; + } + else if (attr.compare("Name") == 0) + { + string name_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *file_name = name_attr_str; + continue; + } + else + return false; + } + return true; + } + + bool fw_logs_xml_helper::get_event_node(xml_node<>* node_event, int* event_id, int* num_of_params, string* line) + { + for (xml_attribute<>* attribute = node_event->first_attribute(); attribute; attribute = attribute->next_attribute()) + { + string attr(attribute->name(), attribute->name() + attribute->name_size()); + + if (attr.compare("id") == 0) + { + string id_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *event_id = stoi(id_attr_str); + continue; + } + else if (attr.compare("numberOfArguments") == 0) + { + string num_of_args_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *num_of_params = stoi(num_of_args_attr_str); + continue; + } + else if (attr.compare("format") == 0) + { + string format_attr_str(attribute->value(), attribute->value() + attribute->value_size()); + *line = format_attr_str; + continue; + } + else + return false; + } + return true; + } + } +} diff --git a/src/fw-logs-parser/fw-logs-xml-helper.h b/src/fw-logs-parser/fw-logs-xml-helper.h new file mode 100644 index 0000000000..ecd3fdc32c --- /dev/null +++ b/src/fw-logs-parser/fw-logs-xml-helper.h @@ -0,0 +1,48 @@ +/* License: Apache 2.0. See LICENSE file in root directory. */ +/* Copyright(c) 2019 Intel Corporation. All Rights Reserved. */ +#pragma once +#include "../../third-party/rapidxml/rapidxml_utils.hpp" +#include "fw-logs-formating-options.h" + +using namespace rapidxml; + +namespace librealsense +{ + namespace fw_logs_parsing + { + class fw_logs_xml_helper + { + public: + enum node_type + { + event, + file, + thread, + enums, + none + }; + + fw_logs_xml_helper(std::string xml_full_file_path); + ~fw_logs_xml_helper(void); + + bool build_log_meta_data(fw_logs_formating_options* logs_formating_options); + + private: + bool init(); + bool build_meta_data_structure(xml_node<>* xml_node_list_of_events, fw_logs_formating_options* logs_formating_options); + node_type get_next_node(xml_node<>* xml_node_list_of_events, int* id, int* num_of_params, std::string* line); + bool get_thread_node(xml_node<>* node_file, int* thread_id, std::string* thread_name); + bool get_event_node(xml_node<>* node_event, int* event_id, int* num_of_params, std::string* line); + bool get_enum_name_node(xml_node<>* node_file, int* thread_id, std::string* thread_name); + bool get_enum_value_node(xml_node<>* node_file, int* thread_id, std::string* enum_name); + bool get_file_node(xml_node<>* node_file, int* file_id, std::string* file_name); + bool get_root_node(xml_node<>** node); + bool try_load_external_xml(); + + bool _init_done; + std::string _xml_full_file_path; + xml_document<> _xml_doc; + std::vector _document_buffer; + }; + } +} diff --git a/src/fw-logs-parser/fw-string-formatter.cpp b/src/fw-logs-parser/fw-string-formatter.cpp new file mode 100644 index 0000000000..72f1348b8a --- /dev/null +++ b/src/fw-logs-parser/fw-string-formatter.cpp @@ -0,0 +1,138 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2019 Intel Corporation. All Rights Reserved. +#include "fw-string-formatter.h" +#include "fw-logs-formating-options.h" +#include +#include +#include +#include + +using namespace std; + +namespace librealsense +{ + namespace fw_logs_parsing + { + fw_string_formatter::fw_string_formatter(std::unordered_map> enums) + :_enums(enums) + { + } + + + fw_string_formatter::~fw_string_formatter(void) + { + } + + bool fw_string_formatter::generate_message(const string& source, size_t num_of_params, const uint32_t* params, string* dest) + { + map exp_replace_map; + map enum_replace_map; + + if (params == nullptr && num_of_params > 0) return false; + + for (size_t i = 0; i < num_of_params; i++) + { + string regular_exp[4]; + string replacement[4]; + stringstream st_regular_exp[4]; + stringstream st_replacement[4]; + + st_regular_exp[0] << "\\{\\b(" << i << ")\\}"; + regular_exp[0] = st_regular_exp[0].str(); + + st_replacement[0] << params[i]; + replacement[0] = st_replacement[0].str(); + + exp_replace_map[regular_exp[0]] = replacement[0]; + + + st_regular_exp[1] << "\\{\\b(" << i << "):x\\}"; + regular_exp[1] = st_regular_exp[1].str(); + + st_replacement[1] << hex << setw(2) << setfill('0') << params[i]; + replacement[1] = st_replacement[1].str(); + + exp_replace_map[regular_exp[1]] = replacement[1]; + + st_regular_exp[2] << "\\{\\b(" << i << "):f\\}"; + regular_exp[2] = st_regular_exp[2].str(); + st_replacement[2] << params[i]; + replacement[2] = st_replacement[2].str(); + exp_replace_map[regular_exp[2]] = replacement[2]; + + + st_regular_exp[3] << "\\{\\b(" << i << "),[a-zA-Z]+\\}"; + regular_exp[3] = st_regular_exp[3].str(); + + enum_replace_map[regular_exp[3]] = params[i]; + } + + return replace_params(source, exp_replace_map, enum_replace_map, dest); + } + + bool fw_string_formatter::replace_params(const string& source, const map& exp_replace_map, const map& enum_replace_map, string* dest) + { + string source_temp(source); + + for (auto exp_replace_it = exp_replace_map.begin(); exp_replace_it != exp_replace_map.end(); exp_replace_it++) + { + string destTemp; + regex e(exp_replace_it->first); + auto res = regex_replace(back_inserter(destTemp), source_temp.begin(), source_temp.end(), e, exp_replace_it->second); + source_temp = destTemp; + } + + for (auto exp_replace_it = enum_replace_map.begin(); exp_replace_it != enum_replace_map.end(); exp_replace_it++) + { + string destTemp; + regex e(exp_replace_it->first); + std::smatch m; + std::regex_search(source_temp, m, std::regex(e)); + + string enum_name; + + string st_regular_exp = "[a-zA-Z]+"; + regex e1(st_regular_exp); + + for (size_t exp = 0; exp < m.size(); exp++) + { + string str = m[exp]; + + std::smatch m1; + + regex e2 = e1; + std::regex_search(str, m1, std::regex(e2)); + + for (size_t exp = 0; exp < m1.size(); exp++) + { + enum_name = m1[exp]; + if (_enums.size() > 0 && _enums.find(enum_name) != _enums.end()) + { + auto vec = _enums[enum_name]; + regex e3 = e; + // Verify user's input is within the enumerated range + int val = exp_replace_it->second; + auto it = std::find_if(vec.begin(), vec.end(), [val](kvp& entry) { return entry.first == val; }); + if (it != vec.end()) + { + regex_replace(back_inserter(destTemp), source_temp.begin(), source_temp.end(), e3, it->second); + } + else + { + stringstream s; + s << "Protocol Error recognized!\nImproper log message received: " << source_temp + << ", invalid parameter: " << exp_replace_it->second << ".\n The range of supported values is \n"; + for_each(vec.begin(), vec.end(), [&s](kvp& entry) { s << entry.first << ":" << entry.second << " ,"; }); + std::cout << s.str().c_str() << std::endl;; + } + source_temp = destTemp; + } + } + } + } + + *dest = source_temp; + return true; + } + } +} diff --git a/src/fw-logs-parser/fw-string-formatter.h b/src/fw-logs-parser/fw-string-formatter.h new file mode 100644 index 0000000000..e54e4a744d --- /dev/null +++ b/src/fw-logs-parser/fw-string-formatter.h @@ -0,0 +1,28 @@ +/* License: Apache 2.0. See LICENSE file in root directory. */ +/* Copyright(c) 2019 Intel Corporation. All Rights Reserved. */ +#pragma once +#include +#include +#include +#include +#include + +namespace librealsense +{ + namespace fw_logs_parsing + { + class fw_string_formatter + { + public: + fw_string_formatter(std::unordered_map>> enums); + ~fw_string_formatter(void); + + bool generate_message(const std::string& source, size_t num_of_params, const uint32_t* params, std::string* dest); + + private: + bool replace_params(const std::string& source, const std::map& exp_replace_map, const std::map& enum_replace_map, std::string* dest); + + std::unordered_map>> _enums; + }; + } +} diff --git a/src/realsense.def b/src/realsense.def index e0bdd94163..47c49f4c76 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -357,6 +357,9 @@ EXPORTS rs2_set_calibration_table rs2_get_firmware_logs + rs2_create_firmware_logs_parser + rs2_delete_firmware_logs_parser + rs2_get_firmware_logs_parsed rs2_create_terminal_parser rs2_delete_terminal_parser diff --git a/src/rs.cpp b/src/rs.cpp index 4fd4942e2a..a0f5941778 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -43,6 +43,7 @@ #include "auto-calibrated-device.h" #include "terminal-parser.h" #include "firmware_logger_device.h" +#include "fw-logs-parser/fw-logs-parser.h" //////////////////////// // API implementation // //////////////////////// @@ -121,6 +122,13 @@ struct rs2_terminal_parser std::shared_ptr terminal_parser; }; +struct rs2_firmware_logs_parser +{ + std::shared_ptr firmware_logs_parser; +}; + + + struct rs2_error { std::string message; @@ -2981,6 +2989,45 @@ const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** er } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev) +rs2_firmware_logs_parser* rs2_create_firmware_logs_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(xml_path); + + return new rs2_firmware_logs_parser{ std::make_shared(xml_path)}; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, xml_path) + +void rs2_delete_firmware_logs_parser(rs2_firmware_logs_parser* parser) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(parser); + delete parser; +} +NOEXCEPT_RETURN(, parser) + +rs2_raw_data_buffer* rs2_get_firmware_logs_parsed(rs2_firmware_logs_parser* fw_logs_parser, const void* raw_data, const int raw_data_size, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_logs_parser); + VALIDATE_NOT_NULL(raw_data); + + std::vector raw_data_buffer((uint8_t*)raw_data, (uint8_t*)raw_data + raw_data_size); + librealsense::fw_logs_parsing::fw_logs_binary_data binary_data = + librealsense::fw_logs_parsing::fw_logs_binary_data{ raw_data_buffer }; + std::vector parsed_data_cpp = fw_logs_parser->firmware_logs_parser.get()->get_fw_log_lines(binary_data); + + // converting vector to vector + std::vector result; + + for (int i = 0; i < parsed_data_cpp.size(); ++i) + { + std::vector current_string_vec(parsed_data_cpp[i].begin(), parsed_data_cpp[i].end()); + result.insert(result.end(), current_string_vec.begin(), current_string_vec.end()); + result.push_back(10); + } + + return new rs2_raw_data_buffer { result }; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_logs_parser, raw_data) + rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_content); @@ -3031,3 +3078,6 @@ rs2_raw_data_buffer* rs2_terminal_parse_response(rs2_terminal_parser* terminal_p return new rs2_raw_data_buffer{ result }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, terminal_parser, command, response) + + + From 367cb7237522a370abd2b8ae576e6fb1d8e13b09 Mon Sep 17 00:00:00 2001 From: remibettan Date: Sun, 17 May 2020 15:23:45 +0300 Subject: [PATCH 04/43] Design change - fw logs returned to user as structure, even without parser --- examples/firmware-logs/rs-firmware-logs.cpp | 36 +++-- include/librealsense2/h/rs_device.h | 14 +- include/librealsense2/hpp/rs_device.hpp | 132 ++++++++++++++++-- include/librealsense2/rs.h | 7 - src/CMakeLists.txt | 2 +- src/firmware_logger_device.cpp | 93 +++++++++++- src/firmware_logger_device.h | 10 +- .../CMakeLists.txt | 0 .../fw-log-data.cpp | 2 +- src/{fw-logs-parser => fw-logs}/fw-log-data.h | 6 +- .../fw-logs-formating-options.cpp | 2 +- .../fw-logs-formating-options.h | 2 +- .../fw-logs-parser.cpp | 29 +++- .../fw-logs-parser.h | 5 +- .../fw-logs-xml-helper.cpp | 2 +- .../fw-logs-xml-helper.h | 2 +- .../fw-string-formatter.cpp | 2 +- .../fw-string-formatter.h | 2 +- src/realsense.def | 1 + src/rs.cpp | 32 +++-- 20 files changed, 327 insertions(+), 54 deletions(-) rename src/{fw-logs-parser => fw-logs}/CMakeLists.txt (100%) rename src/{fw-logs-parser => fw-logs}/fw-log-data.cpp (97%) rename src/{fw-logs-parser => fw-logs}/fw-log-data.h (95%) rename src/{fw-logs-parser => fw-logs}/fw-logs-formating-options.cpp (98%) rename src/{fw-logs-parser => fw-logs}/fw-logs-formating-options.h (98%) rename src/{fw-logs-parser => fw-logs}/fw-logs-parser.cpp (79%) rename src/{fw-logs-parser => fw-logs}/fw-logs-parser.h (82%) rename src/{fw-logs-parser => fw-logs}/fw-logs-xml-helper.cpp (99%) rename src/{fw-logs-parser => fw-logs}/fw-logs-xml-helper.h (98%) rename src/{fw-logs-parser => fw-logs}/fw-string-formatter.cpp (99%) rename src/{fw-logs-parser => fw-logs}/fw-string-formatter.h (96%) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index 40c0ac3765..79c6fc9e6d 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -71,15 +71,15 @@ int main(int argc, char * argv[]) this_thread::sleep_for(chrono::milliseconds(100)); auto fw_log = res.get_device().as(); - std::vector raw_data = fw_log.get_firmware_logs(); + std::vector fw_log_messages = fw_log.get_firmware_logs(); vector fw_log_lines = { "" }; - if (raw_data.size() <= 4) + if (fw_log_messages.size() <= 4) continue; - static bool usingParser = true; + static bool usingParser = false;; if (usingParser) { - std::string xml_path("HWLoggerEventsDS5.xml"); + /*std::string xml_path("HWLoggerEventsDS5.xml"); if (!xml_path.empty()) { ifstream f(xml_path); @@ -87,22 +87,34 @@ int main(int argc, char * argv[]) { unique_ptr parser = unique_ptr(new rs2::firmware_logs_parser(xml_path)); - bool datetime = true; - fw_log_lines = parser->get_firmware_logs_parsed(raw_data); + // first 4 bytes must be deleted - TODO REMI - check why + fw_log_messages.erase(fw_log_messages.begin(), fw_log_messages.begin() + 4); + std::vector one_raw_data; + + auto beginOfLogIterator = fw_log_messages.begin(); + + do { + auto endOfLogIterator = beginOfLogIterator + 20; + one_raw_data.insert(one_raw_data.begin(), beginOfLogIterator, endOfLogIterator); + fw_log_lines.push_back(parser->get_firmware_logs_parsed(one_raw_data)); + beginOfLogIterator = endOfLogIterator; + + if (endOfLogIterator == fw_log_messages.end()) + break; + } while (1); for (auto& elem : fw_log_lines) elem = datetime_string() + " " + elem; } - } - + }*/ } else { stringstream sstr; - sstr << datetime_string() << " FW_Log_Data:"; - for (size_t i = 0; i < raw_data.size(); ++i) - sstr << hexify(raw_data[i]) << " "; - + /*sstr << datetime_string() << " FW_Log_Data:";*/ + for (size_t i = 0; i < fw_log_messages.size(); ++i) + sstr << fw_log_messages[i].to_string() << "\n"; + fw_log_lines.push_back(sstr.str()); } diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index 31903d5905..8d4f496d94 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -353,9 +353,21 @@ rs2_raw_data_buffer* rs2_serialize_json(rs2_device* dev, rs2_error** error); /* Load JSON and apply advanced-mode controls */ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error); -/* Get firmware Logs */ +/** +* \brief Gets RealSense firmware logs. +* \param[in] dev Device from which the FW logs should be taken +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return firmware logs +*/ const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error); +/** +* \brief Gets size of one firmware log. +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return size of one firmware log +*/ +int rs2_get_firmware_logs_one_message_size(rs2_error** error); + /** * \brief Creates RealSense firmware logs parser. * \param[in] xml_path path to xml file needed for parsing diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index 27421d2958..e2de15151f 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -312,6 +312,106 @@ namespace rs2 } }; + class firmware_logger_message + { + public: + firmware_logger_message(const std::vector& fw_log_bytes) + { + int i = 0; + _magic_number = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _severity = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _file_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _group_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _event_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _line = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _sequence = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _p1 = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _p2 = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _p3 = build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _timestamp = build_uint64_from8_uint8(fw_log_bytes.data() + i); + i += 8; + _delta = build_double_from8_uint8(fw_log_bytes.data() + i); + i += 8; + _thread_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); + } + + std::string to_string() const + { + std::stringstream fmt; + fmt << "magic number = " << _magic_number << ",\t" + << "severity = " <<_severity << ",\t" + << "file = " <<_file_id << ",\t" + << "group = " << _group_id << ",\t" + << "line = " << _line << ",\t" + << "sequ = " <<_sequence << ",\t" + << "timestamp = " << _timestamp << ",\t" + << "delta = " << _delta << ",\t" + << "thread = " << _thread_id; + return fmt.str(); + } + + private: + uint32_t build_uint32_from4_uint8(const uint8_t* start) + { + uint8_t first = *(start); + uint8_t second = (*(start + 1)); + uint8_t third = (*(start + 2)); + uint8_t fourth = (*(start + 3)); + uint32_t res = first; + res += static_cast(second << 8); + res += static_cast(third << 16); + res += static_cast(fourth << 24); + return res; + } + + double build_double_from8_uint8(const uint8_t* start) + { + uint64_t resInInt = build_uint64_from8_uint8(start); + double res = *reinterpret_cast(&resInInt); + return res; + } + + uint64_t build_uint64_from8_uint8(const uint8_t* start) + { + uint32_t first = build_uint32_from4_uint8(start); + start += 4; + uint32_t second = build_uint32_from4_uint8(start); + uint64_t res = first; + res += static_cast(second << 32); + + return res; + } + uint32_t _magic_number; + uint32_t _severity; + uint32_t _file_id; + uint32_t _group_id; + uint32_t _event_id; + uint32_t _line; + uint32_t _sequence; + uint32_t _p1; + uint32_t _p2; + uint32_t _p3; + uint64_t _timestamp; + double _delta; + uint32_t _thread_id; + + std::string message; + std::string file_name; + std::string thread_name; + }; + + + class firmware_logger : public device { public: @@ -326,7 +426,7 @@ namespace rs2 error::handle(e); } - std::vector get_firmware_logs() const + std::vector get_firmware_logs() const { std::vector results; @@ -339,11 +439,25 @@ namespace rs2 auto size = rs2_get_raw_data_size(list.get(), &e); error::handle(e); - auto start = rs2_get_raw_data(list.get(), &e); - - results.insert(results.begin(), start, start + size); + auto sizeOfOneLog = rs2_get_firmware_logs_one_message_size(&e); + error::handle(e); - return results; + std::vector vec; + if (size > 0) + { + auto start = rs2_get_raw_data(list.get(), &e); + + results.insert(results.begin(), start, start + size); + auto startIt = results.begin(); + for (int i = 0; i < size / sizeOfOneLog; ++i) + { + std::vector resultsForOneLog; + resultsForOneLog.insert(resultsForOneLog.begin(), startIt, startIt + sizeOfOneLog); + vec.push_back(rs2::firmware_logger_message(resultsForOneLog)); + startIt += sizeOfOneLog; + } + } + return vec; } }; @@ -359,7 +473,7 @@ namespace rs2 error::handle(e); } - std::vector firmware_logs_parser::get_firmware_logs_parsed(const std::vector& raw_data) + std::string firmware_logs_parser::get_firmware_logs_parsed(std::vector& raw_data) { std::string results; @@ -378,7 +492,7 @@ namespace rs2 results.insert(results.begin(), start, start + size); //transforming the string to vector delimiter is '\n' - std::vector log_lines; + /*std::vector log_lines; std::size_t current_start = 0; std::size_t delimiter_found = results.find_first_of("\n"); while (delimiter_found != std::string::npos) @@ -386,9 +500,9 @@ namespace rs2 log_lines.push_back(std::string(results.substr(current_start, delimiter_found - current_start))); current_start = delimiter_found + 1; delimiter_found = results.find_first_of("\n", delimiter_found + 1); - } + }*/ - return log_lines; + return results; } firmware_logs_parser(std::shared_ptr fw_logs_parser) diff --git a/include/librealsense2/rs.h b/include/librealsense2/rs.h index 65fa5be7fe..f43e816461 100644 --- a/include/librealsense2/rs.h +++ b/include/librealsense2/rs.h @@ -110,13 +110,6 @@ float rs2_depth_frame_get_distance(const rs2_frame* frame_ref, int x, int y, rs2 */ rs2_time_t rs2_get_time( rs2_error** error); -/** - * Get Firmware logs - * \param[in] dev The Device - * \param[out] error if non-null, receives any error that occurs during this call, otherwise, errors are ignored - */ -const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error); - #ifdef __cplusplus } #endif diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 9052efa050..9fe5ce02c1 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -11,7 +11,7 @@ include(${_rel_path}/proc/CMakeLists.txt) include(${_rel_path}/res/CMakeLists.txt) include(${_rel_path}/pipeline/CMakeLists.txt) include(${_rel_path}/usb/CMakeLists.txt) -include(${_rel_path}/fw-logs-parser/CMakeLists.txt) +include(${_rel_path}/fw-logs/CMakeLists.txt) include(${_rel_path}/fw-update/CMakeLists.txt) message(STATUS "using ${BACKEND}") diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 970c567a95..c8f093daab 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -8,7 +8,9 @@ namespace librealsense { firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, std::string camera_op_code) : - _hw_monitor(hardware_monitor) + _hw_monitor(hardware_monitor), + _last_timestamp(0), + _timestamp_factor(0.00001) { auto op_code = static_cast(std::stoi(camera_op_code.c_str())); _input_code = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, @@ -17,7 +19,7 @@ namespace librealsense } - std::vector firmware_logger_device::get_fw_logs() const + std::vector firmware_logger_device::get_fw_binary_logs() const { auto res = _hw_monitor->send(_input_code); if (res.empty()) @@ -26,4 +28,91 @@ namespace librealsense } return res; } + + std::vector firmware_logger_device::get_fw_logs() + { + auto res = _hw_monitor->send(_input_code); + if (res.empty()) + { + throw std::runtime_error("Getting Firmware logs failed!"); + } + + //TODO - REMI - check why this is required + res.erase(res.begin(), res.begin() + 4); + + std::vector vec; + auto beginOfLogIterator = res.begin(); + // convert bytes to fw_log_data + for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE; ++i) + { + auto endOfLogIterator = beginOfLogIterator + fw_logs::BINARY_DATA_SIZE; + std::vector resultsForOneLog; + resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); + auto temp_pointer = reinterpret_cast const*>(resultsForOneLog.data()); + auto log = const_cast(reinterpret_cast(temp_pointer)); + + fw_logs::fw_log_data data = fill_log_data(log); + beginOfLogIterator = endOfLogIterator; + + vec.push_back(data); + } + + return vec; + } + + fw_logs::fw_log_data firmware_logger_device::fill_log_data(const char* fw_logs) + { + fw_logs::fw_log_data log_data; + //fw_string_formatter reg_exp(_fw_logs_formating_options.get_enums()); + //fw_log_event log_event_data; + + auto* log_binary = reinterpret_cast(fw_logs); + + //parse first DWORD + log_data.magic_number = static_cast(log_binary->dword1.bits.magic_number); + log_data.severity = static_cast(log_binary->dword1.bits.severity); + + log_data.file_id = static_cast(log_binary->dword1.bits.file_id); + log_data.group_id = static_cast(log_binary->dword1.bits.group_id); + + //parse second DWORD + log_data.event_id = static_cast(log_binary->dword2.bits.event_id); + log_data.line = static_cast(log_binary->dword2.bits.line_id); + log_data.sequence = static_cast(log_binary->dword2.bits.seq_id); + + //parse third DWORD + log_data.p1 = static_cast(log_binary->dword3.p1); + log_data.p2 = static_cast(log_binary->dword3.p2); + + //parse forth DWORD + log_data.p3 = static_cast(log_binary->dword4.p3); + + //parse fifth DWORD + log_data.timestamp = log_binary->dword5.timestamp; + + //------------------------------------------------------------- + if (_last_timestamp == 0) + { + log_data.delta = 0; + } + else + { + log_data.delta = (log_data.timestamp - _last_timestamp) * _timestamp_factor; + } + + _last_timestamp = log_data.timestamp; + + log_data.thread_id = static_cast(log_binary->dword1.bits.thread_id); + //std::string message; + /* + _fw_logs_formating_options.get_event_data(log_data->event_id, &log_event_data); + uint32_t params[3] = { log_data->p1, log_data->p2, log_data->p3 }; + reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &log_data->message); + + _fw_logs_formating_options.get_file_name(log_data->file_id, &log_data->file_name); + _fw_logs_formating_options.get_thread_name(static_cast(log_binary->dword1.bits.thread_id), + &log_data->thread_name);*/ + + return log_data; + } } \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 4456988a98..0b04ff9c65 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -6,13 +6,15 @@ #include "core/extension.h" #include "device.h" #include +#include "fw-logs/fw-log-data.h" namespace librealsense { class firmware_logger_extensions { public: - virtual std::vector get_fw_logs() const = 0; + virtual std::vector get_fw_binary_logs() const = 0; + virtual std::vector get_fw_logs() = 0; virtual ~firmware_logger_extensions() = default; }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); @@ -24,11 +26,15 @@ namespace librealsense firmware_logger_device(std::shared_ptr hardware_monitor, std::string camera_op_code); - std::vector get_fw_logs() const override; + std::vector get_fw_binary_logs() const override; + std::vector get_fw_logs() override; + fw_logs::fw_log_data fill_log_data(const char* fw_logs) ; private: std::vector _input_code; std::shared_ptr _hw_monitor; + uint64_t _last_timestamp; + const double _timestamp_factor; }; } \ No newline at end of file diff --git a/src/fw-logs-parser/CMakeLists.txt b/src/fw-logs/CMakeLists.txt similarity index 100% rename from src/fw-logs-parser/CMakeLists.txt rename to src/fw-logs/CMakeLists.txt diff --git a/src/fw-logs-parser/fw-log-data.cpp b/src/fw-logs/fw-log-data.cpp similarity index 97% rename from src/fw-logs-parser/fw-log-data.cpp rename to src/fw-logs/fw-log-data.cpp index 50d3d4860f..c9c870a9b8 100644 --- a/src/fw-logs-parser/fw-log-data.cpp +++ b/src/fw-logs/fw-log-data.cpp @@ -13,7 +13,7 @@ setfill(' ') << setw(num) << left << element \ namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { fw_log_data::fw_log_data(void) { diff --git a/src/fw-logs-parser/fw-log-data.h b/src/fw-logs/fw-log-data.h similarity index 95% rename from src/fw-logs-parser/fw-log-data.h rename to src/fw-logs/fw-log-data.h index 606d680894..f589f715d9 100644 --- a/src/fw-logs-parser/fw-log-data.h +++ b/src/fw-logs/fw-log-data.h @@ -8,13 +8,15 @@ namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { struct fw_logs_binary_data { std::vector logs_buffer; }; + static const int BINARY_DATA_SIZE = 20; + typedef union { uint32_t value; @@ -84,6 +86,8 @@ namespace librealsense uint64_t timestamp; double delta; + uint32_t thread_id; + std::string message; std::string file_name; std::string thread_name; diff --git a/src/fw-logs-parser/fw-logs-formating-options.cpp b/src/fw-logs/fw-logs-formating-options.cpp similarity index 98% rename from src/fw-logs-parser/fw-logs-formating-options.cpp rename to src/fw-logs/fw-logs-formating-options.cpp index 43e30acf61..1bab57c1af 100644 --- a/src/fw-logs-parser/fw-logs-formating-options.cpp +++ b/src/fw-logs/fw-logs-formating-options.cpp @@ -8,7 +8,7 @@ using namespace std; namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { fw_log_event::fw_log_event() : num_of_params(0), diff --git a/src/fw-logs-parser/fw-logs-formating-options.h b/src/fw-logs/fw-logs-formating-options.h similarity index 98% rename from src/fw-logs-parser/fw-logs-formating-options.h rename to src/fw-logs/fw-logs-formating-options.h index f67a198c95..241f92496f 100644 --- a/src/fw-logs-parser/fw-logs-formating-options.h +++ b/src/fw-logs/fw-logs-formating-options.h @@ -13,7 +13,7 @@ namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { struct fw_log_event { diff --git a/src/fw-logs-parser/fw-logs-parser.cpp b/src/fw-logs/fw-logs-parser.cpp similarity index 79% rename from src/fw-logs-parser/fw-logs-parser.cpp rename to src/fw-logs/fw-logs-parser.cpp index 37c1827cdf..7290a72549 100644 --- a/src/fw-logs-parser/fw-logs-parser.cpp +++ b/src/fw-logs/fw-logs-parser.cpp @@ -10,7 +10,7 @@ using namespace std; namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { fw_logs_parser::fw_logs_parser(string xml_full_file_path) : _fw_logs_formating_options(xml_full_file_path), @@ -28,7 +28,6 @@ namespace librealsense vector fw_logs_parser::get_fw_log_lines(const fw_logs_binary_data& fw_logs_data_binary) { fw_logs_binary_data binary_data = { fw_logs_data_binary }; - binary_data.logs_buffer.erase(binary_data.logs_buffer.begin(), binary_data.logs_buffer.begin() + 4); vector string_vector; int num_of_lines = int(binary_data.logs_buffer.size()) / sizeof(fw_log_binary); auto temp_pointer = reinterpret_cast(binary_data.logs_buffer.data()); @@ -52,6 +51,32 @@ namespace librealsense return log_data.to_string(); } + fw_log_data fw_logs_parser::generate_log_data(char* fw_logs) + { + fw_log_data log_data; + fill_log_data(fw_logs, &log_data); + + return log_data; + } + + vector fw_logs_parser::get_fw_log_data(const fw_logs_binary_data& fw_logs_data_binary) + { + fw_logs_binary_data binary_data = { fw_logs_data_binary }; + vector data_vector; + int num_of_lines = int(binary_data.logs_buffer.size()) / sizeof(fw_log_binary); + auto temp_pointer = reinterpret_cast(binary_data.logs_buffer.data()); + + for (int i = 0; i < num_of_lines; i++) + { + fw_log_data data; + auto log = const_cast(reinterpret_cast(temp_pointer)); + data = generate_log_data(log); + data_vector.push_back(data); + temp_pointer++; + } + return data_vector; + } + void fw_logs_parser::fill_log_data(const char* fw_logs, fw_log_data* log_data) { fw_string_formatter reg_exp(_fw_logs_formating_options.get_enums()); diff --git a/src/fw-logs-parser/fw-logs-parser.h b/src/fw-logs/fw-logs-parser.h similarity index 82% rename from src/fw-logs-parser/fw-logs-parser.h rename to src/fw-logs/fw-logs-parser.h index 7ed135558b..1bfc44ef83 100644 --- a/src/fw-logs-parser/fw-logs-parser.h +++ b/src/fw-logs/fw-logs-parser.h @@ -9,7 +9,7 @@ namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { class fw_logs_parser : public std::enable_shared_from_this { @@ -17,9 +17,12 @@ namespace librealsense explicit fw_logs_parser(std::string xml_full_file_path); ~fw_logs_parser(void); std::vector get_fw_log_lines(const fw_logs_binary_data& fw_logs_data_binary); + std::vector get_fw_log_data(const fw_logs_binary_data& fw_logs_data_binary); + private: std::string generate_log_line(char* fw_logs); + fw_log_data generate_log_data(char* fw_logs); void fill_log_data(const char* fw_logs, fw_log_data* log_data); uint64_t _last_timestamp; diff --git a/src/fw-logs-parser/fw-logs-xml-helper.cpp b/src/fw-logs/fw-logs-xml-helper.cpp similarity index 99% rename from src/fw-logs-parser/fw-logs-xml-helper.cpp rename to src/fw-logs/fw-logs-xml-helper.cpp index a17e1b05e1..03132f65b1 100644 --- a/src/fw-logs-parser/fw-logs-xml-helper.cpp +++ b/src/fw-logs/fw-logs-xml-helper.cpp @@ -10,7 +10,7 @@ using namespace std; namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { fw_logs_xml_helper::fw_logs_xml_helper(string xml_full_file_path) : _init_done(false), diff --git a/src/fw-logs-parser/fw-logs-xml-helper.h b/src/fw-logs/fw-logs-xml-helper.h similarity index 98% rename from src/fw-logs-parser/fw-logs-xml-helper.h rename to src/fw-logs/fw-logs-xml-helper.h index ecd3fdc32c..c9f5a31226 100644 --- a/src/fw-logs-parser/fw-logs-xml-helper.h +++ b/src/fw-logs/fw-logs-xml-helper.h @@ -8,7 +8,7 @@ using namespace rapidxml; namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { class fw_logs_xml_helper { diff --git a/src/fw-logs-parser/fw-string-formatter.cpp b/src/fw-logs/fw-string-formatter.cpp similarity index 99% rename from src/fw-logs-parser/fw-string-formatter.cpp rename to src/fw-logs/fw-string-formatter.cpp index 72f1348b8a..722a25d639 100644 --- a/src/fw-logs-parser/fw-string-formatter.cpp +++ b/src/fw-logs/fw-string-formatter.cpp @@ -11,7 +11,7 @@ using namespace std; namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { fw_string_formatter::fw_string_formatter(std::unordered_map> enums) :_enums(enums) diff --git a/src/fw-logs-parser/fw-string-formatter.h b/src/fw-logs/fw-string-formatter.h similarity index 96% rename from src/fw-logs-parser/fw-string-formatter.h rename to src/fw-logs/fw-string-formatter.h index e54e4a744d..7759e5b7ea 100644 --- a/src/fw-logs-parser/fw-string-formatter.h +++ b/src/fw-logs/fw-string-formatter.h @@ -9,7 +9,7 @@ namespace librealsense { - namespace fw_logs_parsing + namespace fw_logs { class fw_string_formatter { diff --git a/src/realsense.def b/src/realsense.def index 47c49f4c76..5907d008ab 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -357,6 +357,7 @@ EXPORTS rs2_set_calibration_table rs2_get_firmware_logs + rs2_get_firmware_logs_one_message_size rs2_create_firmware_logs_parser rs2_delete_firmware_logs_parser rs2_get_firmware_logs_parsed diff --git a/src/rs.cpp b/src/rs.cpp index a0f5941778..4f50dc2323 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -43,7 +43,7 @@ #include "auto-calibrated-device.h" #include "terminal-parser.h" #include "firmware_logger_device.h" -#include "fw-logs-parser/fw-logs-parser.h" +#include "fw-logs/fw-logs-parser.h" //////////////////////// // API implementation // //////////////////////// @@ -124,11 +124,9 @@ struct rs2_terminal_parser struct rs2_firmware_logs_parser { - std::shared_ptr firmware_logs_parser; + std::shared_ptr firmware_logs_parser; }; - - struct rs2_error { std::string message; @@ -2984,16 +2982,32 @@ const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** er VALIDATE_NOT_NULL(dev); auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - std::vector buffer = fw_loggerable->get_fw_logs(); - return new rs2_raw_data_buffer{ buffer }; + std::vector logs = fw_loggerable->get_fw_logs(); + std::vector buffer; + for (int i = 0; i < logs.size(); ++i) + { + uint32_t size = sizeof(logs[i]); + uint8_t* buf = reinterpret_cast(&logs[i]); + for (int j = 0; j < size; ++j) + { + buffer.push_back(*(buf + j)); + } + } + return new rs2_raw_data_buffer{ buffer }; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev) +int rs2_get_firmware_logs_one_message_size(rs2_error** error) BEGIN_API_CALL +{ + return sizeof(librealsense::fw_logs::fw_log_data); +} +NOEXCEPT_RETURN(0, error) + rs2_firmware_logs_parser* rs2_create_firmware_logs_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_path); - return new rs2_firmware_logs_parser{ std::make_shared(xml_path)}; + return new rs2_firmware_logs_parser{ std::make_shared(xml_path)}; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, xml_path) @@ -3010,8 +3024,8 @@ rs2_raw_data_buffer* rs2_get_firmware_logs_parsed(rs2_firmware_logs_parser* fw_l VALIDATE_NOT_NULL(raw_data); std::vector raw_data_buffer((uint8_t*)raw_data, (uint8_t*)raw_data + raw_data_size); - librealsense::fw_logs_parsing::fw_logs_binary_data binary_data = - librealsense::fw_logs_parsing::fw_logs_binary_data{ raw_data_buffer }; + librealsense::fw_logs::fw_logs_binary_data binary_data = + librealsense::fw_logs::fw_logs_binary_data{ raw_data_buffer }; std::vector parsed_data_cpp = fw_logs_parser->firmware_logs_parser.get()->get_fw_log_lines(binary_data); // converting vector to vector From 7ead7a1ae922997ec7a3a3b40e6f6a27186299c8 Mon Sep 17 00:00:00 2001 From: remibettan Date: Mon, 18 May 2020 10:05:04 +0300 Subject: [PATCH 05/43] FW logs parsing works --- examples/firmware-logs/rs-firmware-logs.cpp | 35 ++-- include/librealsense2/h/rs_device.h | 12 +- include/librealsense2/hpp/rs_device.hpp | 185 ++++++++++++-------- src/fw-logs/CMakeLists.txt | 1 + src/fw-logs/fw-logs-parser.cpp | 104 ++--------- src/fw-logs/fw-logs-parser.h | 8 +- src/realsense.def | 5 +- src/rs.cpp | 39 +++-- 8 files changed, 171 insertions(+), 218 deletions(-) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index 79c6fc9e6d..0db73492af 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -72,14 +72,16 @@ int main(int argc, char * argv[]) auto fw_log = res.get_device().as(); std::vector fw_log_messages = fw_log.get_firmware_logs(); - vector fw_log_lines = { "" }; - if (fw_log_messages.size() <= 4) + + if (fw_log_messages.size() == 0) continue; - static bool usingParser = false;; + std::vector fw_log_lines; + + static bool usingParser = true; if (usingParser) { - /*std::string xml_path("HWLoggerEventsDS5.xml"); + std::string xml_path("HWLoggerEventsDS5.xml"); if (!xml_path.empty()) { ifstream f(xml_path); @@ -87,26 +89,17 @@ int main(int argc, char * argv[]) { unique_ptr parser = unique_ptr(new rs2::firmware_logs_parser(xml_path)); - // first 4 bytes must be deleted - TODO REMI - check why - fw_log_messages.erase(fw_log_messages.begin(), fw_log_messages.begin() + 4); - std::vector one_raw_data; - - auto beginOfLogIterator = fw_log_messages.begin(); - do { - auto endOfLogIterator = beginOfLogIterator + 20; - one_raw_data.insert(one_raw_data.begin(), beginOfLogIterator, endOfLogIterator); - fw_log_lines.push_back(parser->get_firmware_logs_parsed(one_raw_data)); - beginOfLogIterator = endOfLogIterator; - - if (endOfLogIterator == fw_log_messages.end()) - break; - } while (1); + for each (rs2::firmware_logger_message msg in fw_log_messages) + { + parser->parse_firmware_log(msg); + fw_log_lines.push_back(msg.to_string()); + } - for (auto& elem : fw_log_lines) - elem = datetime_string() + " " + elem; + /*for (auto& elem : fw_log_lines) + elem = datetime_string() + " " + elem;*/ } - }*/ + } } else { diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index 8d4f496d94..9a1977060f 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -385,13 +385,17 @@ void rs2_delete_firmware_logs_parser(rs2_firmware_logs_parser* parser); /** * \brief Parses firmware logs. * \param[in] fw_logs_parser firmware logs parser object -* \param[in] raw_data firmware logs not parsed -* \param[in] raw_data_size firmware logs not parsed size +* \param[in] event_id code for event +* \param[in] p1 parameter used to parse the message +* \param[in] p2 parameter used to parse the message +* \param[in] p3 parameter used to parse the message +* \param[in] file_id code for file +* \param[in] thread_id code for the thread * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return firmware logs parsed */ -rs2_raw_data_buffer* rs2_get_firmware_logs_parsed(rs2_firmware_logs_parser* fw_logs_parser, - const void* raw_data, const int raw_data_size, rs2_error** error); +rs2_raw_data_buffer* rs2_parse_firmware_log(rs2_firmware_logs_parser* fw_logs_parser, + int event_id, int p1, int p2, int p3, int file_id, int thread_id, rs2_error** error); #ifdef __cplusplus } diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index e2de15151f..e249cb142a 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -312,56 +312,10 @@ namespace rs2 } }; - class firmware_logger_message + class firmware_logs_helper { public: - firmware_logger_message(const std::vector& fw_log_bytes) - { - int i = 0; - _magic_number = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _severity = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _file_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _group_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _event_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _line = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _sequence = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _p1 = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _p2 = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _p3 = build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _timestamp = build_uint64_from8_uint8(fw_log_bytes.data() + i); - i += 8; - _delta = build_double_from8_uint8(fw_log_bytes.data() + i); - i += 8; - _thread_id = build_uint32_from4_uint8(fw_log_bytes.data() + i); - } - - std::string to_string() const - { - std::stringstream fmt; - fmt << "magic number = " << _magic_number << ",\t" - << "severity = " <<_severity << ",\t" - << "file = " <<_file_id << ",\t" - << "group = " << _group_id << ",\t" - << "line = " << _line << ",\t" - << "sequ = " <<_sequence << ",\t" - << "timestamp = " << _timestamp << ",\t" - << "delta = " << _delta << ",\t" - << "thread = " << _thread_id; - return fmt.str(); - } - - private: - uint32_t build_uint32_from4_uint8(const uint8_t* start) + static uint32_t build_uint32_from4_uint8(const uint8_t* start) { uint8_t first = *(start); uint8_t second = (*(start + 1)); @@ -374,14 +328,14 @@ namespace rs2 return res; } - double build_double_from8_uint8(const uint8_t* start) + static double build_double_from8_uint8(const uint8_t* start) { uint64_t resInInt = build_uint64_from8_uint8(start); double res = *reinterpret_cast(&resInInt); return res; } - uint64_t build_uint64_from8_uint8(const uint8_t* start) + static uint64_t build_uint64_from8_uint8(const uint8_t* start) { uint32_t first = build_uint32_from4_uint8(start); start += 4; @@ -391,6 +345,77 @@ namespace rs2 return res; } + + static std::string build_string_from_uint8_and_size(const uint8_t* start, uint8_t size) + { + std::string res; + res.insert(res.begin(), start, start + size); + return res; + } + }; + + class firmware_logger_message + { + public: + firmware_logger_message(const std::vector& fw_log_bytes) + { + int i = 0; + _magic_number = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _severity = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _file_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _group_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _event_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _line = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _sequence = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _p1 = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _p2 = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _p3 = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + i += 4; + _timestamp = firmware_logs_helper::build_uint64_from8_uint8(fw_log_bytes.data() + i); + i += 8; + _delta = firmware_logs_helper::build_double_from8_uint8(fw_log_bytes.data() + i); + i += 8; + _thread_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); + } + + std::string to_string() const + { + std::stringstream fmt; + if (_message.size() == 0) + { + fmt << "magic number = " << _magic_number << ",\t" + << "severity = " << _severity << ",\t" + << "file = " << _file_id << ",\t" + << "group = " << _group_id << ",\t" + << "line = " << _line << ",\t" + << "sequ = " << _sequence << ",\t" + << "timestamp = " << _timestamp << ",\t" + << "delta = " << _delta << ",\t" + << "thread = " << _thread_id; + } + else + { + fmt << "severity = " << _severity << ",\t" + << "file_name = " << _file_name << ",\t" + << "line = " << _line << ",\t" + << "timestamp = " << _timestamp << ",\t" + << "message = " << _message << ",\t" + << "thread = " << _thread_name; + } + + return fmt.str(); + } + + uint32_t _magic_number; uint32_t _severity; uint32_t _file_id; @@ -405,13 +430,11 @@ namespace rs2 double _delta; uint32_t _thread_id; - std::string message; - std::string file_name; - std::string thread_name; + std::string _message; + std::string _file_name; + std::string _thread_name; }; - - class firmware_logger : public device { public: @@ -473,36 +496,48 @@ namespace rs2 error::handle(e); } - std::string firmware_logs_parser::get_firmware_logs_parsed(std::vector& raw_data) + void parse_firmware_log(rs2::firmware_logger_message& msg) { - std::string results; - rs2_error* e = nullptr; + std::shared_ptr parsed_logs( - rs2_get_firmware_logs_parsed(_firmware_logs_parser.get(), (const void*)raw_data.data(), (const int)raw_data.size(), &e), + rs2_parse_firmware_log(_firmware_logs_parser.get(), + msg._event_id, msg._p1, msg._p2, msg._p3, msg._file_id, msg._thread_id, &e), rs2_delete_raw_data); rs2::error::handle(e); auto size = rs2_get_raw_data_size(parsed_logs.get(), &e); rs2::error::handle(e); - auto start = rs2_get_raw_data(parsed_logs.get(), &e); - rs2::error::handle(e); - - results.insert(results.begin(), start, start + size); - - //transforming the string to vector delimiter is '\n' - /*std::vector log_lines; - std::size_t current_start = 0; - std::size_t delimiter_found = results.find_first_of("\n"); - while (delimiter_found != std::string::npos) + + if (size > 0) { - log_lines.push_back(std::string(results.substr(current_start, delimiter_found - current_start))); - current_start = delimiter_found + 1; - delimiter_found = results.find_first_of("\n", delimiter_found + 1); - }*/ - - return results; + auto start = rs2_get_raw_data(parsed_logs.get(), &e); + + int i = 0; + //retreive message + uint8_t messageSize = *start; + i += 1; + std::string message(firmware_logs_helper::build_string_from_uint8_and_size(start + i, messageSize)); + i += messageSize; + + //retreive file_name + uint8_t fileNameSize = *(start + i); + i += 1; + std::string file_name(firmware_logs_helper::build_string_from_uint8_and_size(start + i, fileNameSize)); + i += fileNameSize; + + //retreive thread_name + uint8_t threadNameSize = *(start + i); + i += 1; + std::string thread_name(firmware_logs_helper::build_string_from_uint8_and_size(start + i, threadNameSize)); + i += threadNameSize; + + //replace in input message + msg._message = message; + msg._file_name = file_name; + msg._thread_name = thread_name; + } } firmware_logs_parser(std::shared_ptr fw_logs_parser) diff --git a/src/fw-logs/CMakeLists.txt b/src/fw-logs/CMakeLists.txt index 33f79d0b81..426bc350ad 100644 --- a/src/fw-logs/CMakeLists.txt +++ b/src/fw-logs/CMakeLists.txt @@ -2,6 +2,7 @@ # Copyright(c) 2020 Intel Corporation. All Rights Reserved. target_sources(${LRS_TARGET} PRIVATE + "${CMAKE_CURRENT_LIST_DIR}/fw-log-data.cpp" "${CMAKE_CURRENT_LIST_DIR}/fw-log-data.h" "${CMAKE_CURRENT_LIST_DIR}/fw-logs-formating-options.cpp" "${CMAKE_CURRENT_LIST_DIR}/fw-logs-formating-options.h" diff --git a/src/fw-logs/fw-logs-parser.cpp b/src/fw-logs/fw-logs-parser.cpp index 7290a72549..0f8231e791 100644 --- a/src/fw-logs/fw-logs-parser.cpp +++ b/src/fw-logs/fw-logs-parser.cpp @@ -13,9 +13,7 @@ namespace librealsense namespace fw_logs { fw_logs_parser::fw_logs_parser(string xml_full_file_path) - : _fw_logs_formating_options(xml_full_file_path), - _last_timestamp(0), - _timestamp_factor(0.00001) + : _fw_logs_formating_options(xml_full_file_path) { _fw_logs_formating_options.initialize_from_xml(); } @@ -25,104 +23,22 @@ namespace librealsense { } - vector fw_logs_parser::get_fw_log_lines(const fw_logs_binary_data& fw_logs_data_binary) + fw_log_data fw_logs_parser::parse_fw_log(uint32_t event_id, uint32_t p1, uint32_t p2, uint32_t p3, + uint32_t file_id, uint32_t thread_id) { - fw_logs_binary_data binary_data = { fw_logs_data_binary }; - vector string_vector; - int num_of_lines = int(binary_data.logs_buffer.size()) / sizeof(fw_log_binary); - auto temp_pointer = reinterpret_cast(binary_data.logs_buffer.data()); + fw_log_data result; - for (int i = 0; i < num_of_lines; i++) - { - string line; - auto log = const_cast(reinterpret_cast(temp_pointer)); - line = generate_log_line(log); - string_vector.push_back(line); - temp_pointer++; - } - return string_vector; - } - - string fw_logs_parser::generate_log_line(char* fw_logs) - { - fw_log_data log_data; - fill_log_data(fw_logs, &log_data); - - return log_data.to_string(); - } - - fw_log_data fw_logs_parser::generate_log_data(char* fw_logs) - { - fw_log_data log_data; - fill_log_data(fw_logs, &log_data); - - return log_data; - } - - vector fw_logs_parser::get_fw_log_data(const fw_logs_binary_data& fw_logs_data_binary) - { - fw_logs_binary_data binary_data = { fw_logs_data_binary }; - vector data_vector; - int num_of_lines = int(binary_data.logs_buffer.size()) / sizeof(fw_log_binary); - auto temp_pointer = reinterpret_cast(binary_data.logs_buffer.data()); - - for (int i = 0; i < num_of_lines; i++) - { - fw_log_data data; - auto log = const_cast(reinterpret_cast(temp_pointer)); - data = generate_log_data(log); - data_vector.push_back(data); - temp_pointer++; - } - return data_vector; - } - - void fw_logs_parser::fill_log_data(const char* fw_logs, fw_log_data* log_data) - { fw_string_formatter reg_exp(_fw_logs_formating_options.get_enums()); fw_log_event log_event_data; - auto* log_binary = reinterpret_cast(fw_logs); - - //parse first DWORD - log_data->magic_number = static_cast(log_binary->dword1.bits.magic_number); - log_data->severity = static_cast(log_binary->dword1.bits.severity); - - log_data->file_id = static_cast(log_binary->dword1.bits.file_id); - log_data->group_id = static_cast(log_binary->dword1.bits.group_id); - - //parse second DWORD - log_data->event_id = static_cast(log_binary->dword2.bits.event_id); - log_data->line = static_cast(log_binary->dword2.bits.line_id); - log_data->sequence = static_cast(log_binary->dword2.bits.seq_id); - - //parse third DWORD - log_data->p1 = static_cast(log_binary->dword3.p1); - log_data->p2 = static_cast(log_binary->dword3.p2); - - //parse forth DWORD - log_data->p3 = static_cast(log_binary->dword4.p3); - - //parse fifth DWORD - log_data->timestamp = log_binary->dword5.timestamp; - - if (_last_timestamp == 0) - { - log_data->delta = 0; - } - else - { - log_data->delta = (log_data->timestamp - _last_timestamp) * _timestamp_factor; - } + _fw_logs_formating_options.get_event_data(event_id, &log_event_data); + uint32_t params[3] = { p1, p2, p3 }; + reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &result.message); - _last_timestamp = log_data->timestamp; - _fw_logs_formating_options.get_event_data(log_data->event_id, &log_event_data); - uint32_t params[3] = { log_data->p1, log_data->p2, log_data->p3 }; - reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &log_data->message); + _fw_logs_formating_options.get_file_name(file_id, &result.file_name); + _fw_logs_formating_options.get_thread_name(static_cast(thread_id), &result.thread_name); - _fw_logs_formating_options.get_file_name(log_data->file_id, &log_data->file_name); - _fw_logs_formating_options.get_thread_name(static_cast(log_binary->dword1.bits.thread_id), - &log_data->thread_name); + return result; } } } diff --git a/src/fw-logs/fw-logs-parser.h b/src/fw-logs/fw-logs-parser.h index 1bfc44ef83..7715561984 100644 --- a/src/fw-logs/fw-logs-parser.h +++ b/src/fw-logs/fw-logs-parser.h @@ -16,18 +16,14 @@ namespace librealsense public: explicit fw_logs_parser(std::string xml_full_file_path); ~fw_logs_parser(void); - std::vector get_fw_log_lines(const fw_logs_binary_data& fw_logs_data_binary); - std::vector get_fw_log_data(const fw_logs_binary_data& fw_logs_data_binary); + fw_log_data parse_fw_log(uint32_t event_id, uint32_t p1, uint32_t p2, uint32_t p3, + uint32_t file_id, uint32_t thread_id); private: - std::string generate_log_line(char* fw_logs); - fw_log_data generate_log_data(char* fw_logs); void fill_log_data(const char* fw_logs, fw_log_data* log_data); - uint64_t _last_timestamp; fw_logs_formating_options _fw_logs_formating_options; - const double _timestamp_factor; }; } } diff --git a/src/realsense.def b/src/realsense.def index 5907d008ab..5478e5b588 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -355,15 +355,16 @@ EXPORTS rs2_run_tare_calibration rs2_get_calibration_table rs2_set_calibration_table - + rs2_get_firmware_logs rs2_get_firmware_logs_one_message_size rs2_create_firmware_logs_parser rs2_delete_firmware_logs_parser - rs2_get_firmware_logs_parsed + rs2_parse_firmware_log rs2_create_terminal_parser rs2_delete_terminal_parser rs2_terminal_parse_command rs2_terminal_parse_response + diff --git a/src/rs.cpp b/src/rs.cpp index 4f50dc2323..cf32596431 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -3018,29 +3018,36 @@ void rs2_delete_firmware_logs_parser(rs2_firmware_logs_parser* parser) BEGIN_API } NOEXCEPT_RETURN(, parser) -rs2_raw_data_buffer* rs2_get_firmware_logs_parsed(rs2_firmware_logs_parser* fw_logs_parser, const void* raw_data, const int raw_data_size, rs2_error** error) BEGIN_API_CALL +rs2_raw_data_buffer* rs2_parse_firmware_log(rs2_firmware_logs_parser* fw_logs_parser, + int event_id, int p1, int p2, int p3, int file_id, int thread_id, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(fw_logs_parser); - VALIDATE_NOT_NULL(raw_data); - std::vector raw_data_buffer((uint8_t*)raw_data, (uint8_t*)raw_data + raw_data_size); - librealsense::fw_logs::fw_logs_binary_data binary_data = - librealsense::fw_logs::fw_logs_binary_data{ raw_data_buffer }; - std::vector parsed_data_cpp = fw_logs_parser->firmware_logs_parser.get()->get_fw_log_lines(binary_data); + librealsense::fw_logs::fw_log_data fw_log = fw_logs_parser->firmware_logs_parser.get()->parse_fw_log(event_id, p1, p2, p3, file_id, thread_id); - // converting vector to vector - std::vector result; + std::vector message_bytes(fw_log.message.begin(), fw_log.message.end()); + message_bytes.push_back('\0'); + uint8_t msg_bytes_size = message_bytes.size(); - for (int i = 0; i < parsed_data_cpp.size(); ++i) - { - std::vector current_string_vec(parsed_data_cpp[i].begin(), parsed_data_cpp[i].end()); - result.insert(result.end(), current_string_vec.begin(), current_string_vec.end()); - result.push_back(10); - } + std::vector file_name_bytes(fw_log.file_name.begin(), fw_log.file_name.end()); + file_name_bytes.push_back('\0'); + uint8_t file_name_bytes_size = file_name_bytes.size(); + + std::vector thread_name_bytes(fw_log.thread_name.begin(), fw_log.thread_name.end()); + thread_name_bytes.push_back('\0'); + uint8_t thread_name_bytes_size = thread_name_bytes.size(); + + std::vector msg_file_thread_bytes; + msg_file_thread_bytes.push_back(msg_bytes_size); + msg_file_thread_bytes.insert(msg_file_thread_bytes.end(), message_bytes.begin(), message_bytes.end()); + msg_file_thread_bytes.push_back(file_name_bytes_size); + msg_file_thread_bytes.insert(msg_file_thread_bytes.end(), file_name_bytes.begin(), file_name_bytes.end()); + msg_file_thread_bytes.push_back(thread_name_bytes_size); + msg_file_thread_bytes.insert(msg_file_thread_bytes.end(), thread_name_bytes.begin(), thread_name_bytes.end()); - return new rs2_raw_data_buffer { result }; + return new rs2_raw_data_buffer { msg_file_thread_bytes }; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_logs_parser, raw_data) +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_logs_parser) rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error) BEGIN_API_CALL { From a599428432504da4ecb68c455d01a094931565a2 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 20 May 2020 21:21:38 +0300 Subject: [PATCH 06/43] FW logs corrected to work with C API - remaining work for the parsing to be more user-friendly --- include/librealsense2/h/rs_device.h | 10 +- include/librealsense2/h/rs_types.h | 28 ++++ include/librealsense2/hpp/rs_device.hpp | 62 +++++---- src/firmware_logger_device.cpp | 31 +++++ src/firmware_logger_device.h | 4 +- src/fw-logs/fw-log-data.cpp | 30 +++++ src/fw-logs/fw-log-data.h | 3 +- src/realsense.def | 4 +- src/rs.cpp | 75 +++++++++-- unit-tests/fw-logs/fw-logs-common.h | 30 +++++ .../fw-logs/test-c-get-fw-logs-not-parsed.cpp | 70 ++++++++++ .../fw-logs/test-c-get-fw-logs-parsed.cpp | 122 ++++++++++++++++++ 12 files changed, 422 insertions(+), 47 deletions(-) create mode 100644 unit-tests/fw-logs/fw-logs-common.h create mode 100644 unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp create mode 100644 unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index 9a1977060f..aeafe048e1 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -359,14 +359,14 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return firmware logs */ -const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error); +rs2_firmware_log_message_list* rs2_get_firmware_logs_list(rs2_device* dev, rs2_error** error); + /** -* \brief Gets size of one firmware log. -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return size of one firmware log +* \brief Frees the relevant firmware logs messages list object. +* \param[in] firmware logs messages list object that is no longer needed */ -int rs2_get_firmware_logs_one_message_size(rs2_error** error); +void rs2_delete_firmware_logs_list(rs2_firmware_log_message_list* fw_logs_list); /** * \brief Creates RealSense firmware logs parser. diff --git a/include/librealsense2/h/rs_types.h b/include/librealsense2/h/rs_types.h index 8c9d01c96f..c709906fce 100644 --- a/include/librealsense2/h/rs_types.h +++ b/include/librealsense2/h/rs_types.h @@ -117,6 +117,34 @@ typedef struct rs2_pose unsigned int mapper_confidence; /**< Pose map confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High */ } rs2_pose; +/** \brief Firmware log message. */ +typedef struct rs2_firmware_log_message +{ + unsigned int _magic_number; /**< magic number at start of the fw log */ + unsigned int _severity; /**< severity of the fw log */ + unsigned int _file_id; /**< id of the file from which the fw log has bee triggered */ + unsigned int _group_id; /**< id of the group from which the fw log has bee triggered */ + unsigned int _event_id; /**< id of the event that the fw log refers to */ + unsigned int _line; /**< line from which the fw log has bee triggered */ + unsigned int _sequence; /**< sequence number from which the fw log has bee triggered */ + unsigned int _p1; /**< parameter for parsing lthe fw log */ + unsigned int _p2; /**< parameter for parsing lthe fw log */ + unsigned int _p3; /**< parameter for parsing lthe fw log */ + unsigned long long _timestamp; /**< timestamp of the fw log */ + double _delta; /**< delta of the timestamp between current and previous fw logs */ + unsigned long long _thread_id; /**< id of the thread from which the fw log has bee triggered */ + + char* _message; /**< fw log message */ + char* _file_name; /**< name of the file from which the fw log has bee triggered */ + char* _thread_name; /**< name of the thread from which the fw log has bee triggered */ +} rs2_firmware_log_message; + +typedef struct rs2_firmware_log_message_list +{ + rs2_firmware_log_message* _messages;/**< pointer to firmware log messages */ + size_t _number_of_messages; /**< number of messages in the member _messages */ +} rs2_firmware_log_message_list; + /** \brief Severity of the librealsense logger. */ typedef enum rs2_log_severity { RS2_LOG_SEVERITY_DEBUG, /**< Detailed information about ordinary operations */ diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index e249cb142a..1fa2bb8483 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -387,6 +387,26 @@ namespace rs2 _thread_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); } + firmware_logger_message(const rs2_firmware_log_message& msg) + { + _magic_number = msg._magic_number; + _severity = msg._severity; + _file_id = msg._file_id; + _group_id = msg._group_id; + _event_id = msg._event_id; + _line = msg._line; + _sequence = msg._sequence; + _p1 = msg._p1; + _p2 = msg._p2; + _p3 = msg._p3; + _timestamp = msg._timestamp; + _delta = msg._delta; + _thread_id = msg._thread_id; + /*_message = std::string(msg._message); + _file_name = std::string(msg._file_name); + _thread_name = std::string(msg._thread_name);*/ + } + std::string to_string() const { std::stringstream fmt; @@ -451,35 +471,29 @@ namespace rs2 std::vector get_firmware_logs() const { - std::vector results; + rs2_error* e = nullptr; - rs2_error* e = nullptr; - std::shared_ptr list( - rs2_get_firmware_logs(_dev.get(), &e), - rs2_delete_raw_data); + std::shared_ptr msg_list( + rs2_get_firmware_logs_list(_dev.get(), &e), + rs2_delete_firmware_logs_list); error::handle(e); - auto size = rs2_get_raw_data_size(list.get(), &e); - error::handle(e); - - auto sizeOfOneLog = rs2_get_firmware_logs_one_message_size(&e); - error::handle(e); - std::vector vec; - if (size > 0) + + if (msg_list) { - auto start = rs2_get_raw_data(list.get(), &e); - - results.insert(results.begin(), start, start + size); - auto startIt = results.begin(); - for (int i = 0; i < size / sizeOfOneLog; ++i) + size_t number_of_messages = msg_list.get()->_number_of_messages > 0; + if (number_of_messages > 0) { - std::vector resultsForOneLog; - resultsForOneLog.insert(resultsForOneLog.begin(), startIt, startIt + sizeOfOneLog); - vec.push_back(rs2::firmware_logger_message(resultsForOneLog)); - startIt += sizeOfOneLog; + // for each message: convert rs2_firmware_log_message to rs2::firmware_log_message + for (int i = 0; i < number_of_messages; ++i) + { + rs2::firmware_logger_message message_received(msg_list.get()->_messages[i]); + vec.push_back(message_received); + } } } + return vec; } }; @@ -500,19 +514,19 @@ namespace rs2 { rs2_error* e = nullptr; - std::shared_ptr parsed_logs( + std::shared_ptr parsed_log( rs2_parse_firmware_log(_firmware_logs_parser.get(), msg._event_id, msg._p1, msg._p2, msg._p3, msg._file_id, msg._thread_id, &e), rs2_delete_raw_data); rs2::error::handle(e); - auto size = rs2_get_raw_data_size(parsed_logs.get(), &e); + auto size = rs2_get_raw_data_size(parsed_log.get(), &e); rs2::error::handle(e); if (size > 0) { - auto start = rs2_get_raw_data(parsed_logs.get(), &e); + auto start = rs2_get_raw_data(parsed_log.get(), &e); int i = 0; //retreive message diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index c8f093daab..4097270443 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -60,6 +60,37 @@ namespace librealsense return vec; } + std::vector firmware_logger_device::get_fw_logs_msg() + { + auto res = _hw_monitor->send(_input_code); + if (res.empty()) + { + throw std::runtime_error("Getting Firmware logs failed!"); + } + + //TODO - REMI - check why this is required + res.erase(res.begin(), res.begin() + 4); + + std::vector vec; + auto beginOfLogIterator = res.begin(); + // convert bytes to rs2_firmware_log_message + for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE; ++i) + { + auto endOfLogIterator = beginOfLogIterator + fw_logs::BINARY_DATA_SIZE; + std::vector resultsForOneLog; + resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); + auto temp_pointer = reinterpret_cast const*>(resultsForOneLog.data()); + auto log = const_cast(reinterpret_cast(temp_pointer)); + + fw_logs::fw_log_data data = fill_log_data(log); + rs2_firmware_log_message msg = data.to_rs2_firmware_log_message(); + beginOfLogIterator = endOfLogIterator; + + vec.push_back(msg); + } + return vec; + } + fw_logs::fw_log_data firmware_logger_device::fill_log_data(const char* fw_logs) { fw_logs::fw_log_data log_data; diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 0b04ff9c65..f65db5ef3d 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -13,8 +13,9 @@ namespace librealsense class firmware_logger_extensions { public: - virtual std::vector get_fw_binary_logs() const = 0; + virtual std::vector get_fw_binary_logs() const = 0; virtual std::vector get_fw_logs() = 0; + virtual std::vector get_fw_logs_msg() = 0; virtual ~firmware_logger_extensions() = default; }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); @@ -28,6 +29,7 @@ namespace librealsense std::vector get_fw_binary_logs() const override; std::vector get_fw_logs() override; + std::vector get_fw_logs_msg() override; fw_logs::fw_log_data fill_log_data(const char* fw_logs) ; private: diff --git a/src/fw-logs/fw-log-data.cpp b/src/fw-logs/fw-log-data.cpp index c9c870a9b8..1f1b6ca5e8 100644 --- a/src/fw-logs/fw-log-data.cpp +++ b/src/fw-logs/fw-log-data.cpp @@ -56,5 +56,35 @@ namespace librealsense auto str = fmt.str(); return str; } + + rs2_firmware_log_message fw_log_data::to_rs2_firmware_log_message() + { + rs2_firmware_log_message msg; + msg._magic_number = this->magic_number; + msg._severity = this->severity; + msg._file_id = this->file_id; + msg._group_id = this->group_id; + msg._event_id = this->event_id; + msg._line = this->line; + msg._sequence = this->sequence; + msg._p1 = this->p1; + msg._p2 = this->p2; + msg._p3 = this->p3; + msg._timestamp = this->timestamp; + msg._thread_id = this->thread_id; + + + //TODO - REMI - check these pointers are deleted in rs2_firmware_log_message destructor + /*msg._message = new char[this->message.size()]; + strcpy(msg._message, this->message.c_str()); + + msg._file_name = new char[this->file_name.size()]; + strcpy(msg._file_name, this->file_name.c_str()); + + msg._thread_name = new char[this->thread_name.size()]; + strcpy(msg._thread_name, this->thread_name.c_str());*/ + + return msg; + } } } diff --git a/src/fw-logs/fw-log-data.h b/src/fw-logs/fw-log-data.h index f589f715d9..585252251e 100644 --- a/src/fw-logs/fw-log-data.h +++ b/src/fw-logs/fw-log-data.h @@ -4,7 +4,7 @@ #include #include #include - +#include "../types.h" //for rs2_firmware_log_message namespace librealsense { @@ -93,6 +93,7 @@ namespace librealsense std::string thread_name; std::string to_string(); + rs2_firmware_log_message to_rs2_firmware_log_message(); }; } } diff --git a/src/realsense.def b/src/realsense.def index 5478e5b588..d10da6b2c4 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -356,8 +356,8 @@ EXPORTS rs2_get_calibration_table rs2_set_calibration_table - rs2_get_firmware_logs - rs2_get_firmware_logs_one_message_size + rs2_get_firmware_logs_list + rs2_delete_firmware_logs_list rs2_create_firmware_logs_parser rs2_delete_firmware_logs_parser rs2_parse_firmware_log diff --git a/src/rs.cpp b/src/rs.cpp index cf32596431..ec64656763 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -2977,31 +2977,78 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s } HANDLE_EXCEPTIONS_AND_RETURN(, dev, json_content, content_size) -const rs2_raw_data_buffer* rs2_get_firmware_logs(rs2_device* dev, rs2_error** error) BEGIN_API_CALL +rs2_firmware_log_message* rs2_get_firmware_logs(rs2_device* dev, int* number_of_messages, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); + VALIDATE_NOT_NULL(number_of_messages); auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + + std::vector logs = fw_loggerable->get_fw_logs(); + *number_of_messages = logs.size(); + rs2_firmware_log_message* list = new rs2_firmware_log_message[*number_of_messages]; + for(int i = 0; i < *number_of_messages; ++i) + { + list[i] = logs[i].to_rs2_firmware_log_message(); + } + + return list; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, number_of_messages, error) + +rs2_firmware_log_message_list* rs2_get_firmware_logs_list(rs2_device* dev, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(dev); + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + std::vector logs = fw_loggerable->get_fw_logs(); - std::vector buffer; - for (int i = 0; i < logs.size(); ++i) + size_t numOfLogs = logs.size(); + + rs2_firmware_log_message* messages = new rs2_firmware_log_message[numOfLogs]; + rs2_firmware_log_message_list* list = new rs2_firmware_log_message_list; + list->_messages = messages; + list->_number_of_messages = logs.size(); + for (size_t i = 0; i < numOfLogs; ++i) { - uint32_t size = sizeof(logs[i]); - uint8_t* buf = reinterpret_cast(&logs[i]); - for (int j = 0; j < size; ++j) - { - buffer.push_back(*(buf + j)); - } + list->_messages[i] = logs[i].to_rs2_firmware_log_message(); } - return new rs2_raw_data_buffer{ buffer }; + + return list; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev) +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, error) -int rs2_get_firmware_logs_one_message_size(rs2_error** error) BEGIN_API_CALL +void rs2_delete_firmware_logs(rs2_firmware_log_message* fw_logs_list) BEGIN_API_CALL { - return sizeof(librealsense::fw_logs::fw_log_data); + VALIDATE_NOT_NULL(fw_logs_list); + + delete[] fw_logs_list[0]._message; + delete[] fw_logs_list[0]._file_name; + delete[] fw_logs_list[0]._thread_name; + + delete[] fw_logs_list; +} +NOEXCEPT_RETURN(, fw_logs_list) + +void rs2_delete_firmware_logs_list(rs2_firmware_log_message_list* fw_logs_list) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_logs_list); + + if (fw_logs_list->_messages) + { + /*for (int i = 0; i < fw_logs_list->_number_of_messages; ++i) + { + if (fw_logs_list->_messages[i]._message) + delete fw_logs_list->_messages[i]._message; + if (fw_logs_list->_messages[i]._file_name) + delete fw_logs_list->_messages[i]._file_name; + if (fw_logs_list->_messages[i]._thread_name) + delete fw_logs_list->_messages[i]._thread_name; + }*/ + delete[] fw_logs_list->_messages; + } + delete[] fw_logs_list; } -NOEXCEPT_RETURN(0, error) +NOEXCEPT_RETURN(, fw_logs_list) rs2_firmware_logs_parser* rs2_create_firmware_logs_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL { diff --git a/unit-tests/fw-logs/fw-logs-common.h b/unit-tests/fw-logs/fw-logs-common.h new file mode 100644 index 0000000000..5609f00be3 --- /dev/null +++ b/unit-tests/fw-logs/fw-logs-common.h @@ -0,0 +1,30 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +#pragma once + +#include // Include RealSense Cross Platform API + + +// Catch also defines CHECK(), and so we have to undefine it or we get compilation errors! +#undef CHECK + +// Let Catch define its own main() function +#define CATCH_CONFIG_MAIN +#include "../catch/catch.hpp" + +// Define our own logging macro for debugging to stdout +// Can possibly turn it on automatically based on the Catch options supplied +// on the command-line, with a custom main(): +// Catch::Session catch_session; +// int main (int argc, char * const argv[]) { +// return catch_session.run( argc, argv ); +// } +// #define TRACE(X) if( catch_session.configData().verbosity == ... ) {} +// With Catch2, we can turn this into SCOPED_INFO. +#define TRACE(X) do { \ + std::cout << X << std::endl; \ + } while(0) + + + diff --git a/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp b/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp new file mode 100644 index 0000000000..3b3b906e30 --- /dev/null +++ b/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp @@ -0,0 +1,70 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +//#cmake:add-file fw-logs-common.h +#include "fw-logs-common.h" + +/* Include the librealsense C header files */ +#include +#include +#include +#include +#include + +char* rs2_firmware_log_message_to_string(rs2_firmware_log_message msg) +{ + char* buffer = (char*)(malloc(50 * sizeof(char))); + sprintf(buffer, "sev = %d, file = %d, line = %d", msg._severity, msg._file_id, msg._line); + return buffer; +} + +//get fw logs using c api +TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { + + rs2_error* e = 0; + + // Create a context object. This object owns the handles to all connected realsense devices. + // The returned object should be released with rs2_delete_context(...) + rs2_context* ctx = rs2_create_context(RS2_API_VERSION, &e); + REQUIRE(e == 0); + + /* Get a list of all the connected devices. */ + // The returned object should be released with rs2_delete_device_list(...) + rs2_device_list* device_list = rs2_query_devices(ctx, &e); + REQUIRE(e == 0); + + int dev_count = rs2_get_device_count(device_list, &e); + REQUIRE(e == 0); + printf("There are %d connected RealSense devices.\n", dev_count); + REQUIRE(dev_count > 0); + + // Get the first connected device + // The returned object should be released with rs2_delete_device(...) + rs2_device* dev = rs2_create_device(device_list, 0, &e); + REQUIRE(e == 0); + + bool device_extendable_to_fw_logger = false; + if (rs2_is_device_extendable_to(dev, RS2_EXTENSION_FW_LOGGER, &e) != 0 && !e) + { + device_extendable_to_fw_logger = true; + } + REQUIRE(device_extendable_to_fw_logger); + + bool were_fw_logs_received_once = false; + while (!were_fw_logs_received_once) + { + rs2_firmware_log_message_list* fw_logs_list = rs2_get_firmware_logs_list(dev, &e); + REQUIRE(fw_logs_list); + + if (fw_logs_list->_number_of_messages > 0) + { + were_fw_logs_received_once = true; + for (int i = 0; i < fw_logs_list->_number_of_messages; ++i) + { + printf("message received: %s\n", rs2_firmware_log_message_to_string(fw_logs_list->_messages[i])); + } + } + rs2_delete_firmware_logs_list(fw_logs_list); + } + +} diff --git a/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp b/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp new file mode 100644 index 0000000000..f961c346a5 --- /dev/null +++ b/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp @@ -0,0 +1,122 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +//#cmake:add-file fw-logs-common.h +#include "fw-logs-common.h" + +/* Include the librealsense C header files */ +#include +#include +#include +#include +#include + + +#include +#define GetCurrentDir _getcwd + +char* rs2_firmware_log_message_to_string(rs2_firmware_log_message msg) +{ + char* buffer = (char*)(malloc(50 * sizeof(char))); + sprintf(buffer, "sev = %d, file = %d, line = %d", msg._severity, msg._file_id, msg._line); + return buffer; +} + + +std::string get_current_dir() { + char buff[FILENAME_MAX]; //create string buffer to hold path + GetCurrentDir(buff, FILENAME_MAX); + std::string current_working_dir(buff); + return current_working_dir; +} + +//get fw logs using c api +TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { + + rs2_error* e = 0; + + // Create a context object. This object owns the handles to all connected realsense devices. + // The returned object should be released with rs2_delete_context(...) + rs2_context* ctx = rs2_create_context(RS2_API_VERSION, &e); + REQUIRE(e == 0); + + /* Get a list of all the connected devices. */ + // The returned object should be released with rs2_delete_device_list(...) + rs2_device_list* device_list = rs2_query_devices(ctx, &e); + REQUIRE(e == 0); + + int dev_count = rs2_get_device_count(device_list, &e); + REQUIRE(e == 0); + printf("There are %d connected RealSense devices.\n", dev_count); + REQUIRE(dev_count > 0); + + // Get the first connected device + // The returned object should be released with rs2_delete_device(...) + rs2_device* dev = rs2_create_device(device_list, 0, &e); + REQUIRE(e == 0); + + bool device_extendable_to_fw_logger = false; + if (rs2_is_device_extendable_to(dev, RS2_EXTENSION_FW_LOGGER, &e) != 0 && !e) + { + device_extendable_to_fw_logger = true; + } + REQUIRE(device_extendable_to_fw_logger); + + const char* xml_path_const = "HWLoggerEventsDS5.xml"; + + /*std::string cf = get_current_dir(); + std::string xml_path(xml_path_const); + + if (!xml_path.empty()) + { + std::ifstream f(xml_path); + if (f.good()) + { + int a = 1; + } + else { + + int b = 1; + } + }*/ + + rs2_firmware_logs_parser* parser = rs2_create_firmware_logs_parser(xml_path_const, &e); + REQUIRE(parser); + + bool were_fw_logs_received_once = false; + while (!were_fw_logs_received_once) + { + rs2_firmware_log_message_list* fw_logs_list = rs2_get_firmware_logs_list(dev, &e); + REQUIRE(fw_logs_list); + + if (fw_logs_list->_number_of_messages > 0) + { + were_fw_logs_received_once = true; + for (int i = 0; i < fw_logs_list->_number_of_messages; ++i) + { + rs2_firmware_log_message* msg = &fw_logs_list->_messages[i]; + rs2_raw_data_buffer* parsed_log = rs2_parse_firmware_log(parser, msg->_event_id, msg->_p1, msg->_p2, msg->_p3, + msg->_file_id, msg->_thread_id, &e); + // call as it must be: rs2_parse_firmware_log(parser, &msg); + rs2::error::handle(e); + + int size = rs2_get_raw_data_size(parsed_log, &e); + rs2::error::handle(e); + + if (size > 0) + { + auto start = rs2_get_raw_data(parsed_log, &e); + + unsigned char message_size = *start; + printf("size of message = %d", message_size); + } + + printf("message received: %s\n", rs2_firmware_log_message_to_string(fw_logs_list->_messages[i])); + } + } + rs2_delete_firmware_logs_list(fw_logs_list); + } + + rs2_delete_firmware_logs_parser(parser); + +} From e3b6c97737f19d337fbbe68d7e8ea389d5f7fa05 Mon Sep 17 00:00:00 2001 From: remibettan Date: Mon, 25 May 2020 10:17:55 +0300 Subject: [PATCH 07/43] API change - Getting logs one by one - parser not operable --- examples/firmware-logs/rs-firmware-logs.cpp | 36 ++-- include/librealsense2/h/rs_device.h | 17 +- include/librealsense2/h/rs_types.h | 31 +-- include/librealsense2/hpp/rs_device.hpp | 183 ++++++------------ src/firmware_logger_device.cpp | 71 ++----- src/firmware_logger_device.h | 13 +- src/fw-logs/fw-log-data.cpp | 30 --- src/fw-logs/fw-logs-parser.cpp | 45 ++++- src/fw-logs/fw-logs-parser.h | 5 +- src/realsense.def | 10 +- src/rs.cpp | 101 ++++------ unit-tests/fw-logs/fw-logs-common.h | 11 +- .../fw-logs/test-c-get-fw-logs-not-parsed.cpp | 41 ++-- .../fw-logs/test-c-get-fw-logs-parsed.cpp | 20 +- 14 files changed, 228 insertions(+), 386 deletions(-) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index 0db73492af..c3c7568f9d 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -68,20 +68,17 @@ int main(int argc, char * argv[]) while (hub.is_connected(dev)) { - this_thread::sleep_for(chrono::milliseconds(100)); + //this_thread::sleep_for(chrono::milliseconds(100)); auto fw_log = res.get_device().as(); - std::vector fw_log_messages = fw_log.get_firmware_logs(); - - if (fw_log_messages.size() == 0) - continue; + auto fw_log_message = fw_log.get_firmware_log(); std::vector fw_log_lines; - static bool usingParser = true; + static bool usingParser = false; if (usingParser) { - std::string xml_path("HWLoggerEventsDS5.xml"); + /*std::string xml_path("HWLoggerEventsDS5.xml"); if (!xml_path.empty()) { ifstream f(xml_path); @@ -90,27 +87,30 @@ int main(int argc, char * argv[]) unique_ptr parser = unique_ptr(new rs2::firmware_logs_parser(xml_path)); - for each (rs2::firmware_logger_message msg in fw_log_messages) + for (rs2::firmware_logger_message msg : fw_log_messages) { parser->parse_firmware_log(msg); fw_log_lines.push_back(msg.to_string()); } - /*for (auto& elem : fw_log_lines) - elem = datetime_string() + " " + elem;*/ + //for (auto& elem : fw_log_lines) + // elem = datetime_string() + " " + elem; } - } + }*/ } else { - stringstream sstr; - /*sstr << datetime_string() << " FW_Log_Data:";*/ - for (size_t i = 0; i < fw_log_messages.size(); ++i) - sstr << fw_log_messages[i].to_string() << "\n"; - - fw_log_lines.push_back(sstr.str()); + if (fw_log_message.size() > 0) + { + stringstream sstr; + sstr << datetime_string() << " FW_Log_Data:"; + for (int i = 0; i < fw_log_message.size(); ++i) + { + sstr << hexify(fw_log_message[i]) << " "; + } + fw_log_lines.push_back(sstr.str()); + } } - for (auto& line : fw_log_lines) cout << line << endl; } diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index aeafe048e1..fce816f5ef 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -359,14 +359,12 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return firmware logs */ -rs2_firmware_log_message_list* rs2_get_firmware_logs_list(rs2_device* dev, rs2_error** error); +rs2_firmware_log_message* rs2_get_firmware_log(rs2_device* dev, rs2_error** error); +void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg); -/** -* \brief Frees the relevant firmware logs messages list object. -* \param[in] firmware logs messages list object that is no longer needed -*/ -void rs2_delete_firmware_logs_list(rs2_firmware_log_message_list* fw_logs_list); +const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); +int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); /** * \brief Creates RealSense firmware logs parser. @@ -374,13 +372,13 @@ void rs2_delete_firmware_logs_list(rs2_firmware_log_message_list* fw_logs_list); * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return firmware logs parser object */ -rs2_firmware_logs_parser* rs2_create_firmware_logs_parser(const char* xml_path, rs2_error** error); +rs2_firmware_log_parser* rs2_create_firmware_log_parser(const char* xml_path, rs2_error** error); /** * \brief Frees the relevant firmware logs parser object. * \param[in] firmware logs parser object that is no longer needed */ -void rs2_delete_firmware_logs_parser(rs2_firmware_logs_parser* parser); +void rs2_delete_firmware_log_parser(rs2_firmware_log_parser* parser); /** * \brief Parses firmware logs. @@ -394,8 +392,7 @@ void rs2_delete_firmware_logs_parser(rs2_firmware_logs_parser* parser); * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return firmware logs parsed */ -rs2_raw_data_buffer* rs2_parse_firmware_log(rs2_firmware_logs_parser* fw_logs_parser, - int event_id, int p1, int p2, int p3, int file_id, int thread_id, rs2_error** error); +//void rs2_parse_firmware_log(rs2_firmware_log_parser* fw_logs_parser, rs2_firmware_log_message** fw_log_msg, rs2_error** error); #ifdef __cplusplus } diff --git a/include/librealsense2/h/rs_types.h b/include/librealsense2/h/rs_types.h index c709906fce..9ebc1613c0 100644 --- a/include/librealsense2/h/rs_types.h +++ b/include/librealsense2/h/rs_types.h @@ -117,34 +117,6 @@ typedef struct rs2_pose unsigned int mapper_confidence; /**< Pose map confidence 0x0 - Failed, 0x1 - Low, 0x2 - Medium, 0x3 - High */ } rs2_pose; -/** \brief Firmware log message. */ -typedef struct rs2_firmware_log_message -{ - unsigned int _magic_number; /**< magic number at start of the fw log */ - unsigned int _severity; /**< severity of the fw log */ - unsigned int _file_id; /**< id of the file from which the fw log has bee triggered */ - unsigned int _group_id; /**< id of the group from which the fw log has bee triggered */ - unsigned int _event_id; /**< id of the event that the fw log refers to */ - unsigned int _line; /**< line from which the fw log has bee triggered */ - unsigned int _sequence; /**< sequence number from which the fw log has bee triggered */ - unsigned int _p1; /**< parameter for parsing lthe fw log */ - unsigned int _p2; /**< parameter for parsing lthe fw log */ - unsigned int _p3; /**< parameter for parsing lthe fw log */ - unsigned long long _timestamp; /**< timestamp of the fw log */ - double _delta; /**< delta of the timestamp between current and previous fw logs */ - unsigned long long _thread_id; /**< id of the thread from which the fw log has bee triggered */ - - char* _message; /**< fw log message */ - char* _file_name; /**< name of the file from which the fw log has bee triggered */ - char* _thread_name; /**< name of the thread from which the fw log has bee triggered */ -} rs2_firmware_log_message; - -typedef struct rs2_firmware_log_message_list -{ - rs2_firmware_log_message* _messages;/**< pointer to firmware log messages */ - size_t _number_of_messages; /**< number of messages in the member _messages */ -} rs2_firmware_log_message_list; - /** \brief Severity of the librealsense logger. */ typedef enum rs2_log_severity { RS2_LOG_SEVERITY_DEBUG, /**< Detailed information about ordinary operations */ @@ -273,6 +245,8 @@ typedef struct rs2_options_list rs2_options_list; typedef struct rs2_devices_changed_callback rs2_devices_changed_callback; typedef struct rs2_notification rs2_notification; typedef struct rs2_notifications_callback rs2_notifications_callback; +typedef struct rs2_firmware_log_message rs2_firmware_log_message; +typedef struct rs2_firmware_log_parser rs2_firmware_log_parser; typedef struct rs2_terminal_parser rs2_terminal_parser; typedef void (*rs2_log_callback_ptr)(rs2_log_severity, rs2_log_message const *, void * arg); typedef void (*rs2_notification_callback_ptr)(rs2_notification*, void*); @@ -281,7 +255,6 @@ typedef void (*rs2_devices_changed_callback_ptr)(rs2_device_list*, rs2_device_li typedef void (*rs2_frame_callback_ptr)(rs2_frame*, void*); typedef void (*rs2_frame_processor_callback_ptr)(rs2_frame*, rs2_source*, void*); typedef void(*rs2_update_progress_callback_ptr)(const float, void*); -typedef struct rs2_firmware_logs_parser rs2_firmware_logs_parser; typedef double rs2_time_t; /**< Timestamp format. units are milliseconds */ typedef long long rs2_metadata_type; /**< Metadata attribute type is defined as 64 bit signed integer*/ diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index 1fa2bb8483..3cce5a9d57 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -354,105 +354,34 @@ namespace rs2 } }; - class firmware_logger_message + + class firmware_log_message { public: - firmware_logger_message(const std::vector& fw_log_bytes) - { - int i = 0; - _magic_number = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _severity = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _file_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _group_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _event_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _line = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _sequence = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _p1 = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _p2 = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _p3 = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - i += 4; - _timestamp = firmware_logs_helper::build_uint64_from8_uint8(fw_log_bytes.data() + i); - i += 8; - _delta = firmware_logs_helper::build_double_from8_uint8(fw_log_bytes.data() + i); - i += 8; - _thread_id = firmware_logs_helper::build_uint32_from4_uint8(fw_log_bytes.data() + i); - } + explicit firmware_log_message(std::shared_ptr msg) + {} + rs2_log_severity get_severity() const; + int size() const { return _fw_log_message.size(); } + uint8_t& operator[] (int i) {return _fw_log_message[i]; } - firmware_logger_message(const rs2_firmware_log_message& msg) - { - _magic_number = msg._magic_number; - _severity = msg._severity; - _file_id = msg._file_id; - _group_id = msg._group_id; - _event_id = msg._event_id; - _line = msg._line; - _sequence = msg._sequence; - _p1 = msg._p1; - _p2 = msg._p2; - _p3 = msg._p3; - _timestamp = msg._timestamp; - _delta = msg._delta; - _thread_id = msg._thread_id; - /*_message = std::string(msg._message); - _file_name = std::string(msg._file_name); - _thread_name = std::string(msg._thread_name);*/ - } - - std::string to_string() const + private: + static firmware_log_message create_from_rs2_firmware_log_message(std::shared_ptr msg) { - std::stringstream fmt; - if (_message.size() == 0) - { - fmt << "magic number = " << _magic_number << ",\t" - << "severity = " << _severity << ",\t" - << "file = " << _file_id << ",\t" - << "group = " << _group_id << ",\t" - << "line = " << _line << ",\t" - << "sequ = " << _sequence << ",\t" - << "timestamp = " << _timestamp << ",\t" - << "delta = " << _delta << ",\t" - << "thread = " << _thread_id; - } - else + rs2_error* e = nullptr; + auto size = rs2_firmware_log_message_size(msg.get(), &e); + std::vector result; + if (size > 0) { - fmt << "severity = " << _severity << ",\t" - << "file_name = " << _file_name << ",\t" - << "line = " << _line << ",\t" - << "timestamp = " << _timestamp << ",\t" - << "message = " << _message << ",\t" - << "thread = " << _thread_name; + auto start = rs2_firmware_log_message_data(msg.get(), &e); + result.insert(result.begin(), start, start + size); } - - return fmt.str(); + return firmware_log_message(result); } - - uint32_t _magic_number; - uint32_t _severity; - uint32_t _file_id; - uint32_t _group_id; - uint32_t _event_id; - uint32_t _line; - uint32_t _sequence; - uint32_t _p1; - uint32_t _p2; - uint32_t _p3; - uint64_t _timestamp; - double _delta; - uint32_t _thread_id; - - std::string _message; - std::string _file_name; - std::string _thread_name; + friend class firmware_logger; + explicit firmware_log_message(std::vector msg) : + _fw_log_message(msg) {} + std::vector _fw_log_message; }; class firmware_logger : public device @@ -469,52 +398,52 @@ namespace rs2 error::handle(e); } - std::vector get_firmware_logs() const + rs2::firmware_log_message get_firmware_log() const { - rs2_error* e = nullptr; - - std::shared_ptr msg_list( - rs2_get_firmware_logs_list(_dev.get(), &e), - rs2_delete_firmware_logs_list); + rs2_error* e = nullptr; + std::shared_ptr msg( + rs2_get_firmware_log(_dev.get(), &e), + rs2_delete_firmware_log_message); error::handle(e); - std::vector vec; - - if (msg_list) - { - size_t number_of_messages = msg_list.get()->_number_of_messages > 0; - if (number_of_messages > 0) - { - // for each message: convert rs2_firmware_log_message to rs2::firmware_log_message - for (int i = 0; i < number_of_messages; ++i) - { - rs2::firmware_logger_message message_received(msg_list.get()->_messages[i]); - vec.push_back(message_received); - } - } - } - - return vec; + return firmware_log_message::create_from_rs2_firmware_log_message(msg); } }; - class firmware_logs_parser + + class firmware_log_parser { public: - firmware_logs_parser(std::string xml_path) + firmware_log_parser(std::string xml_path) { rs2_error* e = nullptr; - _firmware_logs_parser = std::shared_ptr( - rs2_create_firmware_logs_parser(xml_path.data(), &e), - rs2_delete_firmware_logs_parser); + _firmware_log_parser = std::shared_ptr( + rs2_create_firmware_log_parser(xml_path.data(), &e), + rs2_delete_firmware_log_parser); error::handle(e); } - void parse_firmware_log(rs2::firmware_logger_message& msg) + void parse_firmware_log(rs2::firmware_log_message& msg) { - rs2_error* e = nullptr; + /*rs2_error* e = nullptr; + + rs2_firmware_log_message* fw_log_msg = new rs2_firmware_log_message{ msg.to_rs2_firmware_log_message() }; + + if (!fw_log_msg) + return; - std::shared_ptr parsed_log( + rs2_parse_firmware_log(_firmware_logs_parser.get(), &fw_log_msg, &e); + rs2::error::handle(e);*/ + + /*msg._message = std::string(fw_log_msg->_message); + msg._file_name = std::string(fw_log_msg->_file_name); + msg._thread_name = std::string(fw_log_msg->_thread_name); + + delete[] fw_log_msg->_message; + delete[] fw_log_msg->_file_name; + delete[] fw_log_msg->_thread_name; + delete fw_log_msg;*/ + /*std::shared_ptr parsed_log( rs2_parse_firmware_log(_firmware_logs_parser.get(), msg._event_id, msg._p1, msg._p2, msg._p3, msg._file_id, msg._thread_id, &e), rs2_delete_raw_data); @@ -551,16 +480,16 @@ namespace rs2 msg._message = message; msg._file_name = file_name; msg._thread_name = thread_name; - } + }*/ } - firmware_logs_parser(std::shared_ptr fw_logs_parser) - : _firmware_logs_parser(fw_logs_parser) {} + firmware_log_parser(std::shared_ptr fw_log_parser) + : _firmware_log_parser(fw_log_parser) {} - explicit operator std::shared_ptr() { return _firmware_logs_parser; }; + explicit operator std::shared_ptr() { return _firmware_log_parser; }; protected: - std::shared_ptr _firmware_logs_parser; + std::shared_ptr _firmware_log_parser; }; class auto_calibrated_device : public calibrated_device diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 4097270443..d9caae25bd 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -10,7 +10,8 @@ namespace librealsense std::string camera_op_code) : _hw_monitor(hardware_monitor), _last_timestamp(0), - _timestamp_factor(0.00001) + _timestamp_factor(0.00001), + _message_queue() { auto op_code = static_cast(std::stoi(camera_op_code.c_str())); _input_code = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, @@ -19,48 +20,22 @@ namespace librealsense } - std::vector firmware_logger_device::get_fw_binary_logs() const - { - auto res = _hw_monitor->send(_input_code); - if (res.empty()) - { - throw std::runtime_error("Getting Firmware logs failed!"); - } - return res; - } - - std::vector firmware_logger_device::get_fw_logs() - { - auto res = _hw_monitor->send(_input_code); - if (res.empty()) - { - throw std::runtime_error("Getting Firmware logs failed!"); - } - - //TODO - REMI - check why this is required - res.erase(res.begin(), res.begin() + 4); - - std::vector vec; - auto beginOfLogIterator = res.begin(); - // convert bytes to fw_log_data - for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE; ++i) + fw_logs::fw_logs_binary_data firmware_logger_device::get_fw_log() + { + if (_message_queue.empty()) { - auto endOfLogIterator = beginOfLogIterator + fw_logs::BINARY_DATA_SIZE; - std::vector resultsForOneLog; - resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); - auto temp_pointer = reinterpret_cast const*>(resultsForOneLog.data()); - auto log = const_cast(reinterpret_cast(temp_pointer)); - - fw_logs::fw_log_data data = fill_log_data(log); - beginOfLogIterator = endOfLogIterator; - - vec.push_back(data); + get_fw_logs_from_hw_monitor(); } + fw_logs::fw_logs_binary_data result; + if (!_message_queue.empty()) + { + result = _message_queue.front(); + _message_queue.pop(); + } + return result; + } - return vec; - } - - std::vector firmware_logger_device::get_fw_logs_msg() + void firmware_logger_device::get_fw_logs_from_hw_monitor() { auto res = _hw_monitor->send(_input_code); if (res.empty()) @@ -68,29 +43,23 @@ namespace librealsense throw std::runtime_error("Getting Firmware logs failed!"); } - //TODO - REMI - check why this is required + //erasing header res.erase(res.begin(), res.begin() + 4); - std::vector vec; auto beginOfLogIterator = res.begin(); - // convert bytes to rs2_firmware_log_message + // convert bytes to fw_logs_binary_data for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE; ++i) { auto endOfLogIterator = beginOfLogIterator + fw_logs::BINARY_DATA_SIZE; std::vector resultsForOneLog; resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); - auto temp_pointer = reinterpret_cast const*>(resultsForOneLog.data()); - auto log = const_cast(reinterpret_cast(temp_pointer)); - - fw_logs::fw_log_data data = fill_log_data(log); - rs2_firmware_log_message msg = data.to_rs2_firmware_log_message(); + fw_logs::fw_logs_binary_data binary_data{ resultsForOneLog }; + _message_queue.push(binary_data); beginOfLogIterator = endOfLogIterator; - - vec.push_back(msg); } - return vec; } + fw_logs::fw_log_data firmware_logger_device::fill_log_data(const char* fw_logs) { fw_logs::fw_log_data log_data; diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index f65db5ef3d..6babb308b3 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -13,9 +13,7 @@ namespace librealsense class firmware_logger_extensions { public: - virtual std::vector get_fw_binary_logs() const = 0; - virtual std::vector get_fw_logs() = 0; - virtual std::vector get_fw_logs_msg() = 0; + virtual fw_logs::fw_logs_binary_data get_fw_log() = 0; virtual ~firmware_logger_extensions() = default; }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); @@ -27,16 +25,19 @@ namespace librealsense firmware_logger_device(std::shared_ptr hardware_monitor, std::string camera_op_code); - std::vector get_fw_binary_logs() const override; - std::vector get_fw_logs() override; - std::vector get_fw_logs_msg() override; + fw_logs::fw_logs_binary_data get_fw_log() override; + fw_logs::fw_log_data fill_log_data(const char* fw_logs) ; + private: std::vector _input_code; std::shared_ptr _hw_monitor; uint64_t _last_timestamp; const double _timestamp_factor; + + std::queue _message_queue; + void get_fw_logs_from_hw_monitor(); }; } \ No newline at end of file diff --git a/src/fw-logs/fw-log-data.cpp b/src/fw-logs/fw-log-data.cpp index 1f1b6ca5e8..c9c870a9b8 100644 --- a/src/fw-logs/fw-log-data.cpp +++ b/src/fw-logs/fw-log-data.cpp @@ -56,35 +56,5 @@ namespace librealsense auto str = fmt.str(); return str; } - - rs2_firmware_log_message fw_log_data::to_rs2_firmware_log_message() - { - rs2_firmware_log_message msg; - msg._magic_number = this->magic_number; - msg._severity = this->severity; - msg._file_id = this->file_id; - msg._group_id = this->group_id; - msg._event_id = this->event_id; - msg._line = this->line; - msg._sequence = this->sequence; - msg._p1 = this->p1; - msg._p2 = this->p2; - msg._p3 = this->p3; - msg._timestamp = this->timestamp; - msg._thread_id = this->thread_id; - - - //TODO - REMI - check these pointers are deleted in rs2_firmware_log_message destructor - /*msg._message = new char[this->message.size()]; - strcpy(msg._message, this->message.c_str()); - - msg._file_name = new char[this->file_name.size()]; - strcpy(msg._file_name, this->file_name.c_str()); - - msg._thread_name = new char[this->thread_name.size()]; - strcpy(msg._thread_name, this->thread_name.c_str());*/ - - return msg; - } } } diff --git a/src/fw-logs/fw-logs-parser.cpp b/src/fw-logs/fw-logs-parser.cpp index 0f8231e791..348cdde4ef 100644 --- a/src/fw-logs/fw-logs-parser.cpp +++ b/src/fw-logs/fw-logs-parser.cpp @@ -23,22 +23,47 @@ namespace librealsense { } - fw_log_data fw_logs_parser::parse_fw_log(uint32_t event_id, uint32_t p1, uint32_t p2, uint32_t p3, - uint32_t file_id, uint32_t thread_id) + void fw_logs_parser::parse_fw_log(rs2_firmware_log_message** fw_log_msg) { - fw_log_data result; - + /*if (!fw_log_msg || !(*fw_log_msg)) + return; + //message fw_string_formatter reg_exp(_fw_logs_formating_options.get_enums()); fw_log_event log_event_data; + _fw_logs_formating_options.get_event_data((*fw_log_msg)->_event_id, &log_event_data); - _fw_logs_formating_options.get_event_data(event_id, &log_event_data); - uint32_t params[3] = { p1, p2, p3 }; - reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &result.message); + uint32_t params[3] = { (*fw_log_msg)->_p1, (*fw_log_msg)->_p2, (*fw_log_msg)->_p3 }; + std::string parsed_message; + reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &parsed_message); + //reallocate char pointer and copy string into it + /*if ((*fw_log_msg)->_message) + { + delete[] (*fw_log_msg)->_message; + }*/ + /*(*fw_log_msg)->_message = new char[parsed_message.size() + 1]; + strncpy_s((*fw_log_msg)->_message, parsed_message.size() + 1, parsed_message.c_str(), parsed_message.size()); - _fw_logs_formating_options.get_file_name(file_id, &result.file_name); - _fw_logs_formating_options.get_thread_name(static_cast(thread_id), &result.thread_name); + //file name + std::string parsed_file_name; + _fw_logs_formating_options.get_file_name((*fw_log_msg)->_file_id, &parsed_file_name); + //reallocate char pointer and copy string into it + /*if ((*fw_log_msg)->_file_name) + { + delete (*fw_log_msg)->_file_name; + }*/ + /*(*fw_log_msg)->_file_name = new char[parsed_file_name.size() + 1]; + strncpy_s((*fw_log_msg)->_file_name, parsed_file_name.size() + 1, parsed_file_name.c_str(), parsed_file_name.size()); - return result; + //thread name + std::string parsed_thread_name; + _fw_logs_formating_options.get_thread_name(static_cast((*fw_log_msg)->_thread_id), &parsed_thread_name); + //reallocate char pointer and copy string into it + /*if ((*fw_log_msg)->_thread_name) + { + delete (*fw_log_msg)->_thread_name; + }*/ + /*(*fw_log_msg)->_thread_name = new char[parsed_thread_name.size() + 1]; + strncpy_s((*fw_log_msg)->_thread_name, parsed_thread_name.size() + 1, parsed_thread_name.c_str(), parsed_thread_name.size());*/ } } } diff --git a/src/fw-logs/fw-logs-parser.h b/src/fw-logs/fw-logs-parser.h index 7715561984..2f29ed10ee 100644 --- a/src/fw-logs/fw-logs-parser.h +++ b/src/fw-logs/fw-logs-parser.h @@ -16,8 +16,9 @@ namespace librealsense public: explicit fw_logs_parser(std::string xml_full_file_path); ~fw_logs_parser(void); - fw_log_data parse_fw_log(uint32_t event_id, uint32_t p1, uint32_t p2, uint32_t p3, - uint32_t file_id, uint32_t thread_id); + /*fw_log_data parse_fw_log(uint32_t event_id, uint32_t p1, uint32_t p2, uint32_t p3, + uint32_t file_id, uint32_t thread_id);*/ + void fw_logs_parser::parse_fw_log(rs2_firmware_log_message** fw_log_msg); private: diff --git a/src/realsense.def b/src/realsense.def index d10da6b2c4..67b2cae8d1 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -356,10 +356,12 @@ EXPORTS rs2_get_calibration_table rs2_set_calibration_table - rs2_get_firmware_logs_list - rs2_delete_firmware_logs_list - rs2_create_firmware_logs_parser - rs2_delete_firmware_logs_parser + rs2_get_firmware_log + rs2_delete_firmware_log_message + rs2_firmware_log_message_data + rs2_firmware_log_message_size + rs2_create_firmware_log_parser + rs2_delete_firmware_log_parser rs2_parse_firmware_log rs2_create_terminal_parser diff --git a/src/rs.cpp b/src/rs.cpp index ec64656763..55e1500a65 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -122,9 +122,14 @@ struct rs2_terminal_parser std::shared_ptr terminal_parser; }; -struct rs2_firmware_logs_parser +struct rs2_firmware_log_message { - std::shared_ptr firmware_logs_parser; + std::shared_ptr firmware_log_binary_data; +}; + +struct rs2_firmware_log_parser +{ + std::shared_ptr firmware_log_parser; }; struct rs2_error @@ -2977,95 +2982,61 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s } HANDLE_EXCEPTIONS_AND_RETURN(, dev, json_content, content_size) -rs2_firmware_log_message* rs2_get_firmware_logs(rs2_device* dev, int* number_of_messages, rs2_error** error) BEGIN_API_CALL +rs2_firmware_log_message* rs2_get_firmware_log(rs2_device* dev, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); - VALIDATE_NOT_NULL(number_of_messages); auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - std::vector logs = fw_loggerable->get_fw_logs(); - *number_of_messages = logs.size(); - - rs2_firmware_log_message* list = new rs2_firmware_log_message[*number_of_messages]; - for(int i = 0; i < *number_of_messages; ++i) - { - list[i] = logs[i].to_rs2_firmware_log_message(); - } - - return list; + fw_logs::fw_logs_binary_data binary_data = fw_loggerable->get_fw_log(); + return new rs2_firmware_log_message{ std::make_shared(binary_data) }; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, number_of_messages, error) +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, error) -rs2_firmware_log_message_list* rs2_get_firmware_logs_list(rs2_device* dev, rs2_error** error) BEGIN_API_CALL +void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg) BEGIN_API_CALL { - VALIDATE_NOT_NULL(dev); - auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - - std::vector logs = fw_loggerable->get_fw_logs(); - size_t numOfLogs = logs.size(); - - rs2_firmware_log_message* messages = new rs2_firmware_log_message[numOfLogs]; - rs2_firmware_log_message_list* list = new rs2_firmware_log_message_list; - list->_messages = messages; - list->_number_of_messages = logs.size(); - for (size_t i = 0; i < numOfLogs; ++i) - { - list->_messages[i] = logs[i].to_rs2_firmware_log_message(); - } - - return list; + VALIDATE_NOT_NULL(msg); + delete msg; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, error) +NOEXCEPT_RETURN(, msg) -void rs2_delete_firmware_logs(rs2_firmware_log_message* fw_logs_list) BEGIN_API_CALL +const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error)BEGIN_API_CALL { - VALIDATE_NOT_NULL(fw_logs_list); - - delete[] fw_logs_list[0]._message; - delete[] fw_logs_list[0]._file_name; - delete[] fw_logs_list[0]._thread_name; - - delete[] fw_logs_list; + VALIDATE_NOT_NULL(msg); + return msg->firmware_log_binary_data->logs_buffer.data(); } -NOEXCEPT_RETURN(, fw_logs_list) +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, msg) -void rs2_delete_firmware_logs_list(rs2_firmware_log_message_list* fw_logs_list) BEGIN_API_CALL +int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error)BEGIN_API_CALL { - VALIDATE_NOT_NULL(fw_logs_list); - - if (fw_logs_list->_messages) - { - /*for (int i = 0; i < fw_logs_list->_number_of_messages; ++i) - { - if (fw_logs_list->_messages[i]._message) - delete fw_logs_list->_messages[i]._message; - if (fw_logs_list->_messages[i]._file_name) - delete fw_logs_list->_messages[i]._file_name; - if (fw_logs_list->_messages[i]._thread_name) - delete fw_logs_list->_messages[i]._thread_name; - }*/ - delete[] fw_logs_list->_messages; - } - delete[] fw_logs_list; + VALIDATE_NOT_NULL(msg); + return msg->firmware_log_binary_data->logs_buffer.size(); } -NOEXCEPT_RETURN(, fw_logs_list) +HANDLE_EXCEPTIONS_AND_RETURN(0, msg) -rs2_firmware_logs_parser* rs2_create_firmware_logs_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL +rs2_firmware_log_parser* rs2_create_firmware_log_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_path); - return new rs2_firmware_logs_parser{ std::make_shared(xml_path)}; + return new rs2_firmware_log_parser{ std::make_shared(xml_path)}; } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, xml_path) -void rs2_delete_firmware_logs_parser(rs2_firmware_logs_parser* parser) BEGIN_API_CALL +void rs2_delete_firmware_log_parser(rs2_firmware_log_parser* parser) BEGIN_API_CALL { VALIDATE_NOT_NULL(parser); delete parser; } NOEXCEPT_RETURN(, parser) -rs2_raw_data_buffer* rs2_parse_firmware_log(rs2_firmware_logs_parser* fw_logs_parser, +void rs2_parse_firmware_log(rs2_firmware_log_parser* fw_log_parser, rs2_firmware_log_message** fw_log_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_log_parser); + VALIDATE_NOT_NULL(fw_log_msg); + + fw_log_parser->firmware_log_parser.get()->parse_fw_log(fw_log_msg); +} +NOEXCEPT_RETURN(, fw_log_msg) +/*rs2_raw_data_buffer* rs2_parse_firmware_log(rs2_firmware_logs_parser* fw_logs_parser, int event_id, int p1, int p2, int p3, int file_id, int thread_id, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(fw_logs_parser); @@ -3094,7 +3065,7 @@ rs2_raw_data_buffer* rs2_parse_firmware_log(rs2_firmware_logs_parser* fw_logs_pa return new rs2_raw_data_buffer { msg_file_thread_bytes }; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_logs_parser) +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_logs_parser)*/ rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error) BEGIN_API_CALL { diff --git a/unit-tests/fw-logs/fw-logs-common.h b/unit-tests/fw-logs/fw-logs-common.h index 5609f00be3..af25dced2a 100644 --- a/unit-tests/fw-logs/fw-logs-common.h +++ b/unit-tests/fw-logs/fw-logs-common.h @@ -3,8 +3,15 @@ #pragma once -#include // Include RealSense Cross Platform API - +//#include // Include RealSense Cross Platform API + +#include +#ifdef BUILD_SHARED_LIBS +// With static linkage, ELPP is initialized by librealsense, so doing it here will +// create errors. When we're using the shared .so/.dll, the two are separate and we have +// to initialize ours if we want to use the APIs! +INITIALIZE_EASYLOGGINGPP +#endif // Catch also defines CHECK(), and so we have to undefine it or we get compilation errors! #undef CHECK diff --git a/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp b/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp index 3b3b906e30..3da5c82d73 100644 --- a/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp +++ b/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp @@ -6,17 +6,6 @@ /* Include the librealsense C header files */ #include -#include -#include -#include -#include - -char* rs2_firmware_log_message_to_string(rs2_firmware_log_message msg) -{ - char* buffer = (char*)(malloc(50 * sizeof(char))); - sprintf(buffer, "sev = %d, file = %d, line = %d", msg._severity, msg._file_id, msg._line); - return buffer; -} //get fw logs using c api TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { @@ -51,20 +40,36 @@ TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { REQUIRE(device_extendable_to_fw_logger); bool were_fw_logs_received_once = false; - while (!were_fw_logs_received_once) + while (1)//!were_fw_logs_received_once) { - rs2_firmware_log_message_list* fw_logs_list = rs2_get_firmware_logs_list(dev, &e); - REQUIRE(fw_logs_list); + rs2_error* e = nullptr; + rs2_firmware_log_message* fw_log_msg = rs2_get_firmware_log(dev, &e); + + REQUIRE(fw_log_msg); + + int size = rs2_firmware_log_message_size(fw_log_msg, &e); - if (fw_logs_list->_number_of_messages > 0) + auto start = rs2_firmware_log_message_data(fw_log_msg, &e); + + if (size > 0) { were_fw_logs_received_once = true; - for (int i = 0; i < fw_logs_list->_number_of_messages; ++i) + //get time + time_t rawtime; + struct tm* timeinfo; + + time_t mytime = time(NULL); + char* time_str = ctime(&mytime); + time_str[strlen(time_str) - 1] = '\0'; + printf("message received %s - ", time_str); + for (int i = 0; i < size; ++i) { - printf("message received: %s\n", rs2_firmware_log_message_to_string(fw_logs_list->_messages[i])); + printf("%d ", *(start + i)); } + printf("\n"); } - rs2_delete_firmware_logs_list(fw_logs_list); + + rs2_delete_firmware_log_message(fw_log_msg); } } diff --git a/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp b/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp index f961c346a5..57e7a2c341 100644 --- a/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp +++ b/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp @@ -18,7 +18,7 @@ char* rs2_firmware_log_message_to_string(rs2_firmware_log_message msg) { char* buffer = (char*)(malloc(50 * sizeof(char))); - sprintf(buffer, "sev = %d, file = %d, line = %d", msg._severity, msg._file_id, msg._line); + sprintf(buffer, "message = %s", msg._message); return buffer; } @@ -95,23 +95,15 @@ TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { for (int i = 0; i < fw_logs_list->_number_of_messages; ++i) { rs2_firmware_log_message* msg = &fw_logs_list->_messages[i]; - rs2_raw_data_buffer* parsed_log = rs2_parse_firmware_log(parser, msg->_event_id, msg->_p1, msg->_p2, msg->_p3, - msg->_file_id, msg->_thread_id, &e); - // call as it must be: rs2_parse_firmware_log(parser, &msg); - rs2::error::handle(e); + /*rs2_raw_data_buffer* parsed_log = rs2_parse_firmware_log(parser, msg->_event_id, msg->_p1, msg->_p2, msg->_p3, + msg->_file_id, msg->_thread_id, &e);*/ - int size = rs2_get_raw_data_size(parsed_log, &e); + rs2_parse_firmware_log(parser, &msg, &e); rs2::error::handle(e); - if (size > 0) - { - auto start = rs2_get_raw_data(parsed_log, &e); - - unsigned char message_size = *start; - printf("size of message = %d", message_size); - } + printf("message received: %s\n", rs2_firmware_log_message_to_string(*msg)); - printf("message received: %s\n", rs2_firmware_log_message_to_string(fw_logs_list->_messages[i])); + } } rs2_delete_firmware_logs_list(fw_logs_list); From f09c831569dcba79382f73593d024c42b73fa26c Mon Sep 17 00:00:00 2001 From: remibettan Date: Mon, 25 May 2020 11:26:05 +0300 Subject: [PATCH 08/43] get_severity added, firmware_log_message struct improved --- examples/firmware-logs/rs-firmware-logs.cpp | 9 +++-- include/librealsense2/h/rs_device.h | 2 ++ include/librealsense2/hpp/rs_device.hpp | 40 +++++++++++++-------- src/fw-logs/fw-log-data.cpp | 29 +++++++++++++++ src/fw-logs/fw-log-data.h | 3 ++ src/realsense.def | 1 + src/rs.cpp | 6 ++++ 7 files changed, 72 insertions(+), 18 deletions(-) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index c3c7568f9d..2cfe032a16 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -103,10 +103,13 @@ int main(int argc, char * argv[]) if (fw_log_message.size() > 0) { stringstream sstr; - sstr << datetime_string() << " FW_Log_Data:"; - for (int i = 0; i < fw_log_message.size(); ++i) + sstr << datetime_string(); + sstr << " " << fw_log_message.get_severity_str(); + sstr << " FW_Log_Data:"; + std::vector msg_data = fw_log_message.data(); + for (int i = 0; i < msg_data.size(); ++i) { - sstr << hexify(fw_log_message[i]) << " "; + sstr << hexify(msg_data[i]) << " "; } fw_log_lines.push_back(sstr.str()); } diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index fce816f5ef..c70b7fd140 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -366,6 +366,8 @@ void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg); const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); +rs2_log_severity rs2_get_fw_log_severity(const rs2_firmware_log_message* msg, rs2_error** error); + /** * \brief Creates RealSense firmware logs parser. * \param[in] xml_path path to xml file needed for parsing diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index 3cce5a9d57..e9f2bb240b 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -358,30 +358,40 @@ namespace rs2 class firmware_log_message { public: - explicit firmware_log_message(std::shared_ptr msg) - {} - rs2_log_severity get_severity() const; - int size() const { return _fw_log_message.size(); } - uint8_t& operator[] (int i) {return _fw_log_message[i]; } + explicit firmware_log_message(std::shared_ptr msg): + _fw_log_message(msg){} + + rs2_log_severity get_severity() const { + rs2_error* e = nullptr; + rs2_log_severity severity = rs2_get_fw_log_severity(_fw_log_message.get(), &e); + error::handle(e); + return severity; + } + std::string get_severity_str() const { + return rs2_log_severity_to_string(get_severity()); + } - private: - static firmware_log_message create_from_rs2_firmware_log_message(std::shared_ptr msg) + int size() const + { + rs2_error* e = nullptr; + return rs2_firmware_log_message_size(_fw_log_message.get(), &e); + } + + std::vector data() const { rs2_error* e = nullptr; - auto size = rs2_firmware_log_message_size(msg.get(), &e); + auto size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); std::vector result; if (size > 0) { - auto start = rs2_firmware_log_message_data(msg.get(), &e); + auto start = rs2_firmware_log_message_data(_fw_log_message.get(), &e); result.insert(result.begin(), start, start + size); } - return firmware_log_message(result); + return result; } - friend class firmware_logger; - explicit firmware_log_message(std::vector msg) : - _fw_log_message(msg) {} - std::vector _fw_log_message; + private: + std::shared_ptr _fw_log_message; }; class firmware_logger : public device @@ -406,7 +416,7 @@ namespace rs2 rs2_delete_firmware_log_message); error::handle(e); - return firmware_log_message::create_from_rs2_firmware_log_message(msg); + return firmware_log_message(msg); } }; diff --git a/src/fw-logs/fw-log-data.cpp b/src/fw-logs/fw-log-data.cpp index c9c870a9b8..0b37356e53 100644 --- a/src/fw-logs/fw-log-data.cpp +++ b/src/fw-logs/fw-log-data.cpp @@ -56,5 +56,34 @@ namespace librealsense auto str = fmt.str(); return str; } + + rs2_log_severity fw_logs_binary_data::get_severity() const + { + const fw_log_binary* log_binary = reinterpret_cast(logs_buffer.data()); + return fw_logs_severity_to_log_severity(static_cast(log_binary->dword1.bits.severity)); + } + + rs2_log_severity fw_logs_severity_to_log_severity(int32_t severity) + { + rs2_log_severity result = RS2_LOG_SEVERITY_NONE; + switch (severity) + { + case 1: + result = RS2_LOG_SEVERITY_DEBUG; + break; + case 2: + result = RS2_LOG_SEVERITY_WARN; + break; + case 3: + result = RS2_LOG_SEVERITY_ERROR; + break; + case 4: + result = RS2_LOG_SEVERITY_FATAL; + break; + default: + break; + } + return result; + } } } diff --git a/src/fw-logs/fw-log-data.h b/src/fw-logs/fw-log-data.h index 585252251e..429f261eae 100644 --- a/src/fw-logs/fw-log-data.h +++ b/src/fw-logs/fw-log-data.h @@ -13,8 +13,11 @@ namespace librealsense struct fw_logs_binary_data { std::vector logs_buffer; + rs2_log_severity get_severity() const; }; + rs2_log_severity fw_logs_severity_to_log_severity(int32_t severity); + static const int BINARY_DATA_SIZE = 20; typedef union diff --git a/src/realsense.def b/src/realsense.def index 67b2cae8d1..dc0edcca1c 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -358,6 +358,7 @@ EXPORTS rs2_get_firmware_log rs2_delete_firmware_log_message + rs2_get_fw_log_severity rs2_firmware_log_message_data rs2_firmware_log_message_size rs2_create_firmware_log_parser diff --git a/src/rs.cpp b/src/rs.cpp index 55e1500a65..e0511220ba 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -3013,6 +3013,12 @@ int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** err } HANDLE_EXCEPTIONS_AND_RETURN(0, msg) +rs2_log_severity rs2_get_fw_log_severity(const rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL +{ + return msg->firmware_log_binary_data->get_severity(); +} +HANDLE_EXCEPTIONS_AND_RETURN(RS2_LOG_SEVERITY_NONE, msg) + rs2_firmware_log_parser* rs2_create_firmware_log_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_path); From 8e1e606caa6c3dbe8d46d521fa8201921b360910 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 27 May 2020 10:34:50 +0300 Subject: [PATCH 09/43] fw logs messages parsed one by one, API added for timestamp, line, severity, message, file name and thread name --- examples/firmware-logs/rs-firmware-logs.cpp | 25 ++-- include/librealsense2/h/rs_device.h | 114 +++++++++++++-- include/librealsense2/h/rs_types.h | 1 + include/librealsense2/hpp/rs_device.hpp | 138 +++++++++++------- src/firmware_logger_device.cpp | 58 +------- src/firmware_logger_device.h | 5 - src/fw-logs/fw-log-data.cpp | 72 +++++---- src/fw-logs/fw-log-data.h | 41 +++--- src/fw-logs/fw-logs-parser.cpp | 97 +++++++----- src/fw-logs/fw-logs-parser.h | 9 +- src/realsense.def | 10 +- src/rs.cpp | 89 +++++++---- .../fw-logs/test-c-get-fw-logs-not-parsed.cpp | 5 + 13 files changed, 402 insertions(+), 262 deletions(-) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index 2cfe032a16..15249f1b54 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -75,35 +75,34 @@ int main(int argc, char * argv[]) std::vector fw_log_lines; - static bool usingParser = false; + static bool usingParser = true; if (usingParser) { - /*std::string xml_path("HWLoggerEventsDS5.xml"); + std::string xml_path("HWLoggerEventsDS5.xml"); if (!xml_path.empty()) { ifstream f(xml_path); if (f.good()) { - unique_ptr parser = - unique_ptr(new rs2::firmware_logs_parser(xml_path)); + unique_ptr parser = + unique_ptr(new rs2::firmware_log_parser(xml_path)); - for (rs2::firmware_logger_message msg : fw_log_messages) - { - parser->parse_firmware_log(msg); - fw_log_lines.push_back(msg.to_string()); - } + rs2::firmware_log_parsed_message parsed_log = parser->parse_firmware_log(fw_log_message); + stringstream sstr; + sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() + << " " << parsed_log.thread_name() << " " << parsed_log.file_name() + << " " << parsed_log.line(); - //for (auto& elem : fw_log_lines) - // elem = datetime_string() + " " + elem; + fw_log_lines.push_back(sstr.str()); } - }*/ + } } else { if (fw_log_message.size() > 0) { stringstream sstr; - sstr << datetime_string(); + sstr << fw_log_message.get_timestamp(); sstr << " " << fw_log_message.get_severity_str(); sstr << " FW_Log_Data:"; std::vector msg_data = fw_log_message.data(); diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index c70b7fd140..ce11c16563 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -354,19 +354,51 @@ rs2_raw_data_buffer* rs2_serialize_json(rs2_device* dev, rs2_error** error); void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error); /** -* \brief Gets RealSense firmware logs. -* \param[in] dev Device from which the FW logs should be taken -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return firmware logs +* \brief Gets RealSense firmware log. +* \param[in] dev Device from which the FW log should be taken +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return firmware logs */ rs2_firmware_log_message* rs2_get_firmware_log(rs2_device* dev, rs2_error** error); +/** +* Delete RealSense firmware log message +* \param[in] device Realsense firmware log message to delete +*/ void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg); +/** +* \brief Gets RealSense firmware log message data. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to start of the firmware log message data +*/ const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log message size. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return size of the firmware log message data +*/ int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); -rs2_log_severity rs2_get_fw_log_severity(const rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log message timestamp. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return timestamp of the firmware log message +*/ +unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log message severity. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return severity of the firmware log message data +*/ +rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); /** * \brief Creates RealSense firmware logs parser. @@ -383,18 +415,68 @@ rs2_firmware_log_parser* rs2_create_firmware_log_parser(const char* xml_path, rs void rs2_delete_firmware_log_parser(rs2_firmware_log_parser* parser); /** -* \brief Parses firmware logs. -* \param[in] fw_logs_parser firmware logs parser object -* \param[in] event_id code for event -* \param[in] p1 parameter used to parse the message -* \param[in] p2 parameter used to parse the message -* \param[in] p3 parameter used to parse the message -* \param[in] file_id code for file -* \param[in] thread_id code for the thread -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return firmware logs parsed +* \brief Gets RealSense firmware log parser +* \param[in] fw_logs_parser firmware log parser +* \param[in] fw_log_msg firmware log message to be parsed +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return firmware log parsed message +*/ +rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_firmware_log_parser* fw_logs_parser, + rs2_firmware_log_message* fw_log_msg, rs2_error** error); + +/** +* Delete RealSense firmware log parsed message +* \param[in] device Realsense firmware log parsed message to delete +*/ +void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); + +/** +* \brief Gets RealSense firmware log parsed message message. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return message of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message file name. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return file name of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message thread name. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return thread name of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message severity. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return severity of the firmware log parsed message +*/ +rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_log_parsed_file_name). +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return line number of the firmware log parsed message +*/ +unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message timestamp +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return timestamp of the firmware log parsed message */ -//void rs2_parse_firmware_log(rs2_firmware_log_parser* fw_logs_parser, rs2_firmware_log_message** fw_log_msg, rs2_error** error); +unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); #ifdef __cplusplus } diff --git a/include/librealsense2/h/rs_types.h b/include/librealsense2/h/rs_types.h index 9ebc1613c0..075118cf2f 100644 --- a/include/librealsense2/h/rs_types.h +++ b/include/librealsense2/h/rs_types.h @@ -246,6 +246,7 @@ typedef struct rs2_devices_changed_callback rs2_devices_changed_callback; typedef struct rs2_notification rs2_notification; typedef struct rs2_notifications_callback rs2_notifications_callback; typedef struct rs2_firmware_log_message rs2_firmware_log_message; +typedef struct rs2_firmware_log_parsed_message rs2_firmware_log_parsed_message; typedef struct rs2_firmware_log_parser rs2_firmware_log_parser; typedef struct rs2_terminal_parser rs2_terminal_parser; typedef void (*rs2_log_callback_ptr)(rs2_log_severity, rs2_log_message const *, void * arg); diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index e9f2bb240b..eb9b8eb7bf 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -363,7 +363,7 @@ namespace rs2 rs2_log_severity get_severity() const { rs2_error* e = nullptr; - rs2_log_severity severity = rs2_get_fw_log_severity(_fw_log_message.get(), &e); + rs2_log_severity severity = rs2_firmware_log_message_severity(_fw_log_message.get(), &e); error::handle(e); return severity; } @@ -371,25 +371,39 @@ namespace rs2 return rs2_log_severity_to_string(get_severity()); } + uint32_t get_timestamp() const + { + rs2_error* e = nullptr; + uint32_t timestamp = rs2_firmware_log_message_timestamp(_fw_log_message.get(), &e); + error::handle(e); + return timestamp; + } + int size() const { rs2_error* e = nullptr; - return rs2_firmware_log_message_size(_fw_log_message.get(), &e); + int size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); + error::handle(e); + return size; } std::vector data() const { rs2_error* e = nullptr; auto size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); + error::handle(e); std::vector result; if (size > 0) { auto start = rs2_firmware_log_message_data(_fw_log_message.get(), &e); + error::handle(e); result.insert(result.begin(), start, start + size); } return result; } + const std::shared_ptr get_message() const { return _fw_log_message; } + private: std::shared_ptr _fw_log_message; }; @@ -420,6 +434,59 @@ namespace rs2 } }; + class firmware_log_parsed_message + { + public: + explicit firmware_log_parsed_message(std::shared_ptr msg) : + _parsed_fw_log(msg) {} + + std::string message() const + { + rs2_error* e = nullptr; + std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e)); + error::handle(e); + return msg; + } + std::string file_name() const + { + rs2_error* e = nullptr; + std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return file_name; + } + std::string thread_name() const + { + rs2_error* e = nullptr; + std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return thread_name; + } + std::string severity() const + { + rs2_error* e = nullptr; + rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e); + error::handle(e); + return std::string(rs2_log_severity_to_string(sev)); + } + uint32_t line() const + { + rs2_error* e = nullptr; + uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e)); + error::handle(e); + return line; + } + uint32_t timestamp() const + { + rs2_error* e = nullptr; + uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e)); + error::handle(e); + return timestamp; + } + + private: + std::shared_ptr _parsed_fw_log; + }; + class firmware_log_parser { @@ -433,64 +500,23 @@ namespace rs2 error::handle(e); } - void parse_firmware_log(rs2::firmware_log_message& msg) + rs2::firmware_log_parsed_message parse_firmware_log(const rs2::firmware_log_message& msg) { - /*rs2_error* e = nullptr; - - rs2_firmware_log_message* fw_log_msg = new rs2_firmware_log_message{ msg.to_rs2_firmware_log_message() }; - - if (!fw_log_msg) - return; - - rs2_parse_firmware_log(_firmware_logs_parser.get(), &fw_log_msg, &e); - rs2::error::handle(e);*/ - - /*msg._message = std::string(fw_log_msg->_message); - msg._file_name = std::string(fw_log_msg->_file_name); - msg._thread_name = std::string(fw_log_msg->_thread_name); + rs2_error* e = nullptr; - delete[] fw_log_msg->_message; - delete[] fw_log_msg->_file_name; - delete[] fw_log_msg->_thread_name; - delete fw_log_msg;*/ - /*std::shared_ptr parsed_log( - rs2_parse_firmware_log(_firmware_logs_parser.get(), - msg._event_id, msg._p1, msg._p2, msg._p3, msg._file_id, msg._thread_id, &e), - rs2_delete_raw_data); - rs2::error::handle(e); + auto size = rs2_firmware_log_message_size(msg.get_message().get(), &e); + error::handle(e); + if (size == 0) + { + // TODO - handle this case, or let the user handle it... + } - auto size = rs2_get_raw_data_size(parsed_log.get(), &e); - rs2::error::handle(e); + std::shared_ptr parsed_msg( + rs2_parse_firmware_log(_firmware_log_parser.get(), msg.get_message().get(), &e), + rs2_delete_firmware_log_parsed_message); + error::handle(e); - - if (size > 0) - { - auto start = rs2_get_raw_data(parsed_log.get(), &e); - - int i = 0; - //retreive message - uint8_t messageSize = *start; - i += 1; - std::string message(firmware_logs_helper::build_string_from_uint8_and_size(start + i, messageSize)); - i += messageSize; - - //retreive file_name - uint8_t fileNameSize = *(start + i); - i += 1; - std::string file_name(firmware_logs_helper::build_string_from_uint8_and_size(start + i, fileNameSize)); - i += fileNameSize; - - //retreive thread_name - uint8_t threadNameSize = *(start + i); - i += 1; - std::string thread_name(firmware_logs_helper::build_string_from_uint8_and_size(start + i, threadNameSize)); - i += threadNameSize; - - //replace in input message - msg._message = message; - msg._file_name = file_name; - msg._thread_name = thread_name; - }*/ + return firmware_log_parsed_message(parsed_msg); } firmware_log_parser(std::shared_ptr fw_log_parser) diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index d9caae25bd..df096041d5 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -9,8 +9,6 @@ namespace librealsense firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, std::string camera_op_code) : _hw_monitor(hardware_monitor), - _last_timestamp(0), - _timestamp_factor(0.00001), _message_queue() { auto op_code = static_cast(std::stoi(camera_op_code.c_str())); @@ -60,59 +58,5 @@ namespace librealsense } - fw_logs::fw_log_data firmware_logger_device::fill_log_data(const char* fw_logs) - { - fw_logs::fw_log_data log_data; - //fw_string_formatter reg_exp(_fw_logs_formating_options.get_enums()); - //fw_log_event log_event_data; - - auto* log_binary = reinterpret_cast(fw_logs); - - //parse first DWORD - log_data.magic_number = static_cast(log_binary->dword1.bits.magic_number); - log_data.severity = static_cast(log_binary->dword1.bits.severity); - - log_data.file_id = static_cast(log_binary->dword1.bits.file_id); - log_data.group_id = static_cast(log_binary->dword1.bits.group_id); - - //parse second DWORD - log_data.event_id = static_cast(log_binary->dword2.bits.event_id); - log_data.line = static_cast(log_binary->dword2.bits.line_id); - log_data.sequence = static_cast(log_binary->dword2.bits.seq_id); - - //parse third DWORD - log_data.p1 = static_cast(log_binary->dword3.p1); - log_data.p2 = static_cast(log_binary->dword3.p2); - - //parse forth DWORD - log_data.p3 = static_cast(log_binary->dword4.p3); - - //parse fifth DWORD - log_data.timestamp = log_binary->dword5.timestamp; - - //------------------------------------------------------------- - if (_last_timestamp == 0) - { - log_data.delta = 0; - } - else - { - log_data.delta = (log_data.timestamp - _last_timestamp) * _timestamp_factor; - } - - _last_timestamp = log_data.timestamp; - - log_data.thread_id = static_cast(log_binary->dword1.bits.thread_id); - //std::string message; - /* - _fw_logs_formating_options.get_event_data(log_data->event_id, &log_event_data); - uint32_t params[3] = { log_data->p1, log_data->p2, log_data->p3 }; - reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &log_data->message); - - _fw_logs_formating_options.get_file_name(log_data->file_id, &log_data->file_name); - _fw_logs_formating_options.get_thread_name(static_cast(log_binary->dword1.bits.thread_id), - &log_data->thread_name);*/ - - return log_data; - } + } \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 6babb308b3..a96dd8fda5 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -27,14 +27,9 @@ namespace librealsense fw_logs::fw_logs_binary_data get_fw_log() override; - fw_logs::fw_log_data fill_log_data(const char* fw_logs) ; - - private: std::vector _input_code; std::shared_ptr _hw_monitor; - uint64_t _last_timestamp; - const double _timestamp_factor; std::queue _message_queue; void get_fw_logs_from_hw_monitor(); diff --git a/src/fw-logs/fw-log-data.cpp b/src/fw-logs/fw-log-data.cpp index 0b37356e53..60560d5abc 100644 --- a/src/fw-logs/fw-log-data.cpp +++ b/src/fw-logs/fw-log-data.cpp @@ -17,20 +17,20 @@ namespace librealsense { fw_log_data::fw_log_data(void) { - magic_number = 0; - severity = 0; - file_id = 0; - group_id = 0; - event_id = 0; - line = 0; - sequence = 0; - p1 = 0; - p2 = 0; - p3 = 0; - timestamp = 0; - delta = 0; - message = ""; - file_name = ""; + _magic_number = 0; + _severity = 0; + _file_id = 0; + _group_id = 0; + _event_id = 0; + _line = 0; + _sequence = 0; + _p1 = 0; + _p2 = 0; + _p3 = 0; + _timestamp = 0; + _delta = 0; + _message = ""; + _file_name = ""; } @@ -39,22 +39,34 @@ namespace librealsense } - string fw_log_data::to_string() + rs2_log_severity fw_log_data::get_severity() const { - stringstream fmt; + return fw_logs_severity_to_log_severity(_severity); + } - fmt << SET_WIDTH_AND_FILL(6, sequence) - << SET_WIDTH_AND_FILL(30, file_name) - << SET_WIDTH_AND_FILL(6, group_id) - << SET_WIDTH_AND_FILL(15, thread_name) - << SET_WIDTH_AND_FILL(6, severity) - << SET_WIDTH_AND_FILL(6, line) - << SET_WIDTH_AND_FILL(15, timestamp) - << SET_WIDTH_AND_FILL(15, delta) - << SET_WIDTH_AND_FILL(30, message); + const std::string& fw_log_data::get_message() const + { + return _message; + } - auto str = fmt.str(); - return str; + const std::string& fw_log_data::get_file_name() const + { + return _file_name; + } + + const std::string& fw_log_data::get_thread_name() const + { + return _thread_name; + } + + uint32_t fw_log_data::get_line() const + { + return _line; + } + + uint32_t fw_log_data::get_timestamp() const + { + return _timestamp; } rs2_log_severity fw_logs_binary_data::get_severity() const @@ -63,6 +75,12 @@ namespace librealsense return fw_logs_severity_to_log_severity(static_cast(log_binary->dword1.bits.severity)); } + uint32_t fw_logs_binary_data::get_timestamp() const + { + const fw_log_binary* log_binary = reinterpret_cast(logs_buffer.data()); + return static_cast(log_binary->dword5.timestamp); + } + rs2_log_severity fw_logs_severity_to_log_severity(int32_t severity) { rs2_log_severity result = RS2_LOG_SEVERITY_NONE; diff --git a/src/fw-logs/fw-log-data.h b/src/fw-logs/fw-log-data.h index 429f261eae..62774dc68c 100644 --- a/src/fw-logs/fw-log-data.h +++ b/src/fw-logs/fw-log-data.h @@ -14,6 +14,7 @@ namespace librealsense { std::vector logs_buffer; rs2_log_severity get_severity() const; + uint32_t get_timestamp() const; }; rs2_log_severity fw_logs_severity_to_log_severity(int32_t severity); @@ -76,27 +77,31 @@ namespace librealsense fw_log_data(void); ~fw_log_data(void); - uint32_t magic_number; - uint32_t severity; - uint32_t file_id; - uint32_t group_id; - uint32_t event_id; - uint32_t line; - uint32_t sequence; - uint32_t p1; - uint32_t p2; - uint32_t p3; - uint64_t timestamp; - double delta; + uint32_t _magic_number; + uint32_t _severity; + uint32_t _file_id; + uint32_t _group_id; + uint32_t _event_id; + uint32_t _line; + uint32_t _sequence; + uint32_t _p1; + uint32_t _p2; + uint32_t _p3; + uint64_t _timestamp; + double _delta; - uint32_t thread_id; + uint32_t _thread_id; - std::string message; - std::string file_name; - std::string thread_name; + std::string _message; + std::string _file_name; + std::string _thread_name; - std::string to_string(); - rs2_firmware_log_message to_rs2_firmware_log_message(); + rs2_log_severity get_severity() const; + const std::string& get_message() const; + const std::string& get_file_name() const; + const std::string& get_thread_name() const; + uint32_t get_line() const; + uint32_t get_timestamp() const; }; } } diff --git a/src/fw-logs/fw-logs-parser.cpp b/src/fw-logs/fw-logs-parser.cpp index 348cdde4ef..7e57f6579f 100644 --- a/src/fw-logs/fw-logs-parser.cpp +++ b/src/fw-logs/fw-logs-parser.cpp @@ -13,7 +13,9 @@ namespace librealsense namespace fw_logs { fw_logs_parser::fw_logs_parser(string xml_full_file_path) - : _fw_logs_formating_options(xml_full_file_path) + : _fw_logs_formating_options(xml_full_file_path), + _last_timestamp(0), + _timestamp_factor(0.00001) { _fw_logs_formating_options.initialize_from_xml(); } @@ -23,47 +25,66 @@ namespace librealsense { } - void fw_logs_parser::parse_fw_log(rs2_firmware_log_message** fw_log_msg) + fw_log_data fw_logs_parser::parse_fw_log(const fw_logs_binary_data* fw_log_msg) { - /*if (!fw_log_msg || !(*fw_log_msg)) - return; + fw_log_data log_data; + + if (!fw_log_msg || fw_log_msg->logs_buffer.size() == 0) + return log_data; + + log_data = fill_log_data(fw_log_msg); + //message fw_string_formatter reg_exp(_fw_logs_formating_options.get_enums()); fw_log_event log_event_data; - _fw_logs_formating_options.get_event_data((*fw_log_msg)->_event_id, &log_event_data); - - uint32_t params[3] = { (*fw_log_msg)->_p1, (*fw_log_msg)->_p2, (*fw_log_msg)->_p3 }; - std::string parsed_message; - reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &parsed_message); - //reallocate char pointer and copy string into it - /*if ((*fw_log_msg)->_message) - { - delete[] (*fw_log_msg)->_message; - }*/ - /*(*fw_log_msg)->_message = new char[parsed_message.size() + 1]; - strncpy_s((*fw_log_msg)->_message, parsed_message.size() + 1, parsed_message.c_str(), parsed_message.size()); - - //file name - std::string parsed_file_name; - _fw_logs_formating_options.get_file_name((*fw_log_msg)->_file_id, &parsed_file_name); - //reallocate char pointer and copy string into it - /*if ((*fw_log_msg)->_file_name) - { - delete (*fw_log_msg)->_file_name; - }*/ - /*(*fw_log_msg)->_file_name = new char[parsed_file_name.size() + 1]; - strncpy_s((*fw_log_msg)->_file_name, parsed_file_name.size() + 1, parsed_file_name.c_str(), parsed_file_name.size()); - - //thread name - std::string parsed_thread_name; - _fw_logs_formating_options.get_thread_name(static_cast((*fw_log_msg)->_thread_id), &parsed_thread_name); - //reallocate char pointer and copy string into it - /*if ((*fw_log_msg)->_thread_name) - { - delete (*fw_log_msg)->_thread_name; - }*/ - /*(*fw_log_msg)->_thread_name = new char[parsed_thread_name.size() + 1]; - strncpy_s((*fw_log_msg)->_thread_name, parsed_thread_name.size() + 1, parsed_thread_name.c_str(), parsed_thread_name.size());*/ + _fw_logs_formating_options.get_event_data(log_data._event_id, &log_event_data); + + uint32_t params[3] = { log_data._p1, log_data._p2, log_data._p3 }; + reg_exp.generate_message(log_event_data.line, log_event_data.num_of_params, params, &log_data._message); + + //file_name + _fw_logs_formating_options.get_file_name(log_data._file_id, &log_data._file_name); + + //thread_name + _fw_logs_formating_options.get_thread_name(log_data._thread_id, &log_data._thread_name); + + return log_data; + } + + fw_log_data fw_logs_parser::fill_log_data(const fw_logs_binary_data* fw_log_msg) + { + fw_log_data log_data; + + auto* log_binary = reinterpret_cast(fw_log_msg->logs_buffer.data()); + + //parse first DWORD + log_data._magic_number = static_cast(log_binary->dword1.bits.magic_number); + log_data._severity = static_cast(log_binary->dword1.bits.severity); + log_data._thread_id = static_cast(log_binary->dword1.bits.thread_id); + log_data._file_id = static_cast(log_binary->dword1.bits.file_id); + log_data._group_id = static_cast(log_binary->dword1.bits.group_id); + + //parse second DWORD + log_data._event_id = static_cast(log_binary->dword2.bits.event_id); + log_data._line = static_cast(log_binary->dword2.bits.line_id); + log_data._sequence = static_cast(log_binary->dword2.bits.seq_id); + + //parse third DWORD + log_data._p1 = static_cast(log_binary->dword3.p1); + log_data._p2 = static_cast(log_binary->dword3.p2); + + //parse forth DWORD + log_data._p3 = static_cast(log_binary->dword4.p3); + + //parse fifth DWORD + log_data._timestamp = log_binary->dword5.timestamp; + + log_data._delta = (_last_timestamp == 0) ? + 0 :(log_data._timestamp - _last_timestamp) * _timestamp_factor; + + _last_timestamp = log_data._timestamp; + + return log_data; } } } diff --git a/src/fw-logs/fw-logs-parser.h b/src/fw-logs/fw-logs-parser.h index 2f29ed10ee..faeb6c5b26 100644 --- a/src/fw-logs/fw-logs-parser.h +++ b/src/fw-logs/fw-logs-parser.h @@ -16,15 +16,16 @@ namespace librealsense public: explicit fw_logs_parser(std::string xml_full_file_path); ~fw_logs_parser(void); - /*fw_log_data parse_fw_log(uint32_t event_id, uint32_t p1, uint32_t p2, uint32_t p3, - uint32_t file_id, uint32_t thread_id);*/ - void fw_logs_parser::parse_fw_log(rs2_firmware_log_message** fw_log_msg); + + fw_log_data fw_logs_parser::parse_fw_log(const fw_logs_binary_data* fw_log_msg); private: - void fill_log_data(const char* fw_logs, fw_log_data* log_data); + fw_log_data fill_log_data(const fw_logs_binary_data* fw_log_msg); fw_logs_formating_options _fw_logs_formating_options; + uint64_t _last_timestamp; + const double _timestamp_factor; }; } } diff --git a/src/realsense.def b/src/realsense.def index dc0edcca1c..0c14a205df 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -358,12 +358,20 @@ EXPORTS rs2_get_firmware_log rs2_delete_firmware_log_message - rs2_get_fw_log_severity + rs2_firmware_log_message_severity + rs2_firmware_log_message_timestamp rs2_firmware_log_message_data rs2_firmware_log_message_size rs2_create_firmware_log_parser rs2_delete_firmware_log_parser rs2_parse_firmware_log + rs2_delete_firmware_log_parsed_message + rs2_get_fw_log_parsed_message + rs2_get_fw_log_parsed_file_name + rs2_get_fw_log_parsed_thread_name + rs2_get_fw_log_parsed_severity + rs2_get_fw_log_parsed_line + rs2_get_fw_log_parsed_timestamp rs2_create_terminal_parser rs2_delete_terminal_parser diff --git a/src/rs.cpp b/src/rs.cpp index e0511220ba..a22e28ef9c 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -127,6 +127,11 @@ struct rs2_firmware_log_message std::shared_ptr firmware_log_binary_data; }; +struct rs2_firmware_log_parsed_message +{ + std::shared_ptr firmware_log_parsed; +}; + struct rs2_firmware_log_parser { std::shared_ptr firmware_log_parser; @@ -3013,12 +3018,19 @@ int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** err } HANDLE_EXCEPTIONS_AND_RETURN(0, msg) -rs2_log_severity rs2_get_fw_log_severity(const rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL +rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL { return msg->firmware_log_binary_data->get_severity(); } HANDLE_EXCEPTIONS_AND_RETURN(RS2_LOG_SEVERITY_NONE, msg) +unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(msg); + return msg->firmware_log_binary_data->get_timestamp(); +} +HANDLE_EXCEPTIONS_AND_RETURN(0, msg) + rs2_firmware_log_parser* rs2_create_firmware_log_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_path); @@ -3034,44 +3046,67 @@ void rs2_delete_firmware_log_parser(rs2_firmware_log_parser* parser) BEGIN_API_C } NOEXCEPT_RETURN(, parser) -void rs2_parse_firmware_log(rs2_firmware_log_parser* fw_log_parser, rs2_firmware_log_message** fw_log_msg, rs2_error** error) BEGIN_API_CALL +rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_firmware_log_parser* fw_log_parser, rs2_firmware_log_message* fw_log_msg, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(fw_log_parser); VALIDATE_NOT_NULL(fw_log_msg); - fw_log_parser->firmware_log_parser.get()->parse_fw_log(fw_log_msg); + librealsense::fw_logs::fw_log_data log_data = + fw_log_parser->firmware_log_parser.get()->parse_fw_log(fw_log_msg->firmware_log_binary_data.get()); + + return new rs2_firmware_log_parsed_message{ std::make_shared(log_data) }; } -NOEXCEPT_RETURN(, fw_log_msg) -/*rs2_raw_data_buffer* rs2_parse_firmware_log(rs2_firmware_logs_parser* fw_logs_parser, - int event_id, int p1, int p2, int p3, int file_id, int thread_id, rs2_error** error) BEGIN_API_CALL +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_msg) + +void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg) BEGIN_API_CALL { - VALIDATE_NOT_NULL(fw_logs_parser); + VALIDATE_NOT_NULL(fw_log_parsed_msg); + delete fw_log_parsed_msg; +} +NOEXCEPT_RETURN(, fw_log_parsed_msg) - librealsense::fw_logs::fw_log_data fw_log = fw_logs_parser->firmware_logs_parser.get()->parse_fw_log(event_id, p1, p2, p3, file_id, thread_id); - - std::vector message_bytes(fw_log.message.begin(), fw_log.message.end()); - message_bytes.push_back('\0'); - uint8_t msg_bytes_size = message_bytes.size(); +const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_log_parsed_msg); + return fw_log_parsed_msg->firmware_log_parsed->get_message().c_str(); +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_parsed_msg) + +const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_log_parsed_msg); + return fw_log_parsed_msg->firmware_log_parsed->get_file_name().c_str(); +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_parsed_msg) - std::vector file_name_bytes(fw_log.file_name.begin(), fw_log.file_name.end()); - file_name_bytes.push_back('\0'); - uint8_t file_name_bytes_size = file_name_bytes.size(); +const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_log_parsed_msg); + return fw_log_parsed_msg->firmware_log_parsed->get_thread_name().c_str(); +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_parsed_msg) - std::vector thread_name_bytes(fw_log.thread_name.begin(), fw_log.thread_name.end()); - thread_name_bytes.push_back('\0'); - uint8_t thread_name_bytes_size = thread_name_bytes.size(); +rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_log_parsed_msg); + return fw_log_parsed_msg->firmware_log_parsed->get_severity(); +} +HANDLE_EXCEPTIONS_AND_RETURN(RS2_LOG_SEVERITY_NONE, fw_log_parsed_msg) - std::vector msg_file_thread_bytes; - msg_file_thread_bytes.push_back(msg_bytes_size); - msg_file_thread_bytes.insert(msg_file_thread_bytes.end(), message_bytes.begin(), message_bytes.end()); - msg_file_thread_bytes.push_back(file_name_bytes_size); - msg_file_thread_bytes.insert(msg_file_thread_bytes.end(), file_name_bytes.begin(), file_name_bytes.end()); - msg_file_thread_bytes.push_back(thread_name_bytes_size); - msg_file_thread_bytes.insert(msg_file_thread_bytes.end(), thread_name_bytes.begin(), thread_name_bytes.end()); +unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_log_parsed_msg); + return fw_log_parsed_msg->firmware_log_parsed->get_line(); +} +HANDLE_EXCEPTIONS_AND_RETURN(0, fw_log_parsed_msg) - return new rs2_raw_data_buffer { msg_file_thread_bytes }; +unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(fw_log_parsed_msg); + return fw_log_parsed_msg->firmware_log_parsed->get_timestamp(); } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_logs_parser)*/ +HANDLE_EXCEPTIONS_AND_RETURN(0, fw_log_parsed_msg) + rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error) BEGIN_API_CALL { diff --git a/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp b/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp index 3da5c82d73..73cfbc890d 100644 --- a/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp +++ b/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp @@ -62,6 +62,11 @@ TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { char* time_str = ctime(&mytime); time_str[strlen(time_str) - 1] = '\0'; printf("message received %s - ", time_str); + + rs2_error* e = nullptr; + rs2_log_severity severity = rs2_get_fw_log_severity(fw_log_msg, &e); + printf("%s ", rs2_log_severity_to_string(severity)); + for (int i = 0; i < size; ++i) { printf("%d ", *(start + i)); From 5c651e9c2c0d42cfe83b319b3aea1b891a0be02e Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 27 May 2020 14:09:48 +0300 Subject: [PATCH 10/43] fw log message provided as input to get firmware logs --- examples/firmware-logs/rs-firmware-logs.cpp | 56 ++++++++++----------- include/librealsense2/h/rs_device.h | 18 +++++-- include/librealsense2/hpp/rs_device.hpp | 20 +++++--- src/firmware_logger_device.cpp | 11 ++-- src/firmware_logger_device.h | 4 +- src/realsense.def | 3 +- src/rs.cpp | 23 +++++++-- 7 files changed, 84 insertions(+), 51 deletions(-) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index 15249f1b54..bc4cb22c4a 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -67,39 +67,37 @@ int main(int argc, char * argv[]) setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout while (hub.is_connected(dev)) - { - //this_thread::sleep_for(chrono::milliseconds(100)); - + { auto fw_log = res.get_device().as(); - auto fw_log_message = fw_log.get_firmware_log(); - - std::vector fw_log_lines; - - static bool usingParser = true; - if (usingParser) + auto fw_log_message = fw_log.create_message(); + bool result = fw_log.get_firmware_log(fw_log_message); + if (result) { - std::string xml_path("HWLoggerEventsDS5.xml"); - if (!xml_path.empty()) + std::vector fw_log_lines; + + static bool usingParser = true; + if (usingParser) { - ifstream f(xml_path); - if (f.good()) + std::string xml_path("HWLoggerEventsDS5.xml"); + if (!xml_path.empty()) { - unique_ptr parser = - unique_ptr(new rs2::firmware_log_parser(xml_path)); - - rs2::firmware_log_parsed_message parsed_log = parser->parse_firmware_log(fw_log_message); - stringstream sstr; - sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() - << " " << parsed_log.thread_name() << " " << parsed_log.file_name() - << " " << parsed_log.line(); - - fw_log_lines.push_back(sstr.str()); + ifstream f(xml_path); + if (f.good()) + { + unique_ptr parser = + unique_ptr(new rs2::firmware_log_parser(xml_path)); + + rs2::firmware_log_parsed_message parsed_log = parser->parse_firmware_log(fw_log_message); + stringstream sstr; + sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() + << " " << parsed_log.thread_name() << " " << parsed_log.file_name() + << " " << parsed_log.line(); + + fw_log_lines.push_back(sstr.str()); + } } } - } - else - { - if (fw_log_message.size() > 0) + else { stringstream sstr; sstr << fw_log_message.get_timestamp(); @@ -112,9 +110,9 @@ int main(int argc, char * argv[]) } fw_log_lines.push_back(sstr.str()); } + for (auto& line : fw_log_lines) + cout << line << endl; } - for (auto& line : fw_log_lines) - cout << line << endl; } } catch (const rs2::error & e) diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index ce11c16563..da03320dd3 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -354,13 +354,21 @@ rs2_raw_data_buffer* rs2_serialize_json(rs2_device* dev, rs2_error** error); void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error); /** -* \brief Gets RealSense firmware log. -* \param[in] dev Device from which the FW log should be taken -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return firmware logs +* \brief Creates RealSense firmware log message. +* \param[in] dev Device from which the FW log will be taken using the created message +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to created empty firmware log message */ -rs2_firmware_log_message* rs2_get_firmware_log(rs2_device* dev, rs2_error** error); +rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_error** error); +/** +* \brief Gets RealSense firmware log. +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor +*/ +int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); /** * Delete RealSense firmware log message * \param[in] device Realsense firmware log message to delete diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index eb9b8eb7bf..91c2273510 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -422,16 +422,28 @@ namespace rs2 error::handle(e); } - rs2::firmware_log_message get_firmware_log() const + rs2::firmware_log_message create_message() { rs2_error* e = nullptr; std::shared_ptr msg( - rs2_get_firmware_log(_dev.get(), &e), + rs2_create_firmware_log_message(_dev.get(), &e), rs2_delete_firmware_log_message); error::handle(e); return firmware_log_message(msg); } + + bool get_firmware_log(rs2::firmware_log_message& msg) const + { + rs2_error* e = nullptr; + rs2_firmware_log_message* m = msg.get_message().get(); + bool fw_log_pulling_status = + rs2_get_firmware_log(_dev.get(), &(m), &e); + + error::handle(e); + + return fw_log_pulling_status; + } }; class firmware_log_parsed_message @@ -506,10 +518,6 @@ namespace rs2 auto size = rs2_firmware_log_message_size(msg.get_message().get(), &e); error::handle(e); - if (size == 0) - { - // TODO - handle this case, or let the user handle it... - } std::shared_ptr parsed_msg( rs2_parse_firmware_log(_firmware_log_parser.get(), msg.get_message().get(), &e), diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index df096041d5..b71e8c4951 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -17,18 +17,21 @@ namespace librealsense 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; } - - fw_logs::fw_logs_binary_data firmware_logger_device::get_fw_log() + bool firmware_logger_device::get_fw_log(fw_logs::fw_logs_binary_data& binary_data) { + bool result = false; if (_message_queue.empty()) { get_fw_logs_from_hw_monitor(); } - fw_logs::fw_logs_binary_data result; + if (!_message_queue.empty()) { - result = _message_queue.front(); + fw_logs::fw_logs_binary_data data; + data = _message_queue.front(); _message_queue.pop(); + binary_data = data; + result = true; } return result; } diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index a96dd8fda5..616c62fc32 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -13,7 +13,7 @@ namespace librealsense class firmware_logger_extensions { public: - virtual fw_logs::fw_logs_binary_data get_fw_log() = 0; + virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual ~firmware_logger_extensions() = default; }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); @@ -25,7 +25,7 @@ namespace librealsense firmware_logger_device(std::shared_ptr hardware_monitor, std::string camera_op_code); - fw_logs::fw_logs_binary_data get_fw_log() override; + bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; private: std::vector _input_code; diff --git a/src/realsense.def b/src/realsense.def index 0c14a205df..52830ef0cf 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -356,8 +356,9 @@ EXPORTS rs2_get_calibration_table rs2_set_calibration_table - rs2_get_firmware_log + rs2_create_firmware_log_message rs2_delete_firmware_log_message + rs2_get_firmware_log rs2_firmware_log_message_severity rs2_firmware_log_message_timestamp rs2_firmware_log_message_data diff --git a/src/rs.cpp b/src/rs.cpp index a22e28ef9c..9e09c76bdb 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -2987,15 +2987,30 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s } HANDLE_EXCEPTIONS_AND_RETURN(, dev, json_content, content_size) -rs2_firmware_log_message* rs2_get_firmware_log(rs2_device* dev, rs2_error** error) BEGIN_API_CALL +rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_error** error)BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + + return new rs2_firmware_log_message{ std::make_shared () }; +} +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev) + +int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(dev); + VALIDATE_NOT_NULL(fw_log_msg); + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - fw_logs::fw_logs_binary_data binary_data = fw_loggerable->get_fw_log(); - return new rs2_firmware_log_message{ std::make_shared(binary_data) }; + fw_logs::fw_logs_binary_data binary_data; + bool result = fw_loggerable->get_fw_log(binary_data); + if (result) + { + (*(*fw_log_msg)->firmware_log_binary_data.get()) = binary_data; + } + return result? 1 : 0; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, error) +HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg) void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg) BEGIN_API_CALL { From cc747b249b7d74682e707a3137cf2e1d81fb377f Mon Sep 17 00:00:00 2001 From: remibettan Date: Sun, 31 May 2020 16:08:25 +0300 Subject: [PATCH 11/43] Flash logs work - work to do in fw logger device - see comment --- examples/CMakeLists.txt | 1 + examples/flash-logs/CMakeLists.txt | 16 +++ examples/flash-logs/rs-flash-logs.cpp | 126 ++++++++++++++++++++++++ include/librealsense2/h/rs_device.h | 12 +++ include/librealsense2/hpp/rs_device.hpp | 23 +++++ src/firmware_logger_device.cpp | 123 ++++++++++++++++++++--- src/firmware_logger_device.h | 24 ++++- src/fw-logs/fw-logs-parser.h | 2 +- src/realsense.def | 1 + src/rs.cpp | 28 ++++++ 10 files changed, 336 insertions(+), 20 deletions(-) create mode 100644 examples/flash-logs/CMakeLists.txt create mode 100644 examples/flash-logs/rs-flash-logs.cpp diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index c01d08be23..8f1a688f36 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -48,3 +48,4 @@ add_subdirectory(ar-advanced) add_subdirectory(pose-apriltag) add_subdirectory(tracking-and-depth) add_subdirectory(firmware-logs) +add_subdirectory(flash-logs) diff --git a/examples/flash-logs/CMakeLists.txt b/examples/flash-logs/CMakeLists.txt new file mode 100644 index 0000000000..fac7fe82c8 --- /dev/null +++ b/examples/flash-logs/CMakeLists.txt @@ -0,0 +1,16 @@ +# License: Apache 2.0. See LICENSE file in root directory. +# Copyright(c) 2020 Intel Corporation. All Rights Reserved. +# minimum required cmake version: 3.1.0 +cmake_minimum_required(VERSION 3.1.0) + +project(RealsenseExamplesFirmwareLogs) + +if(BUILD_GRAPHICAL_EXAMPLES) + add_executable(rs-flash-logs rs-flash-logs.cpp ../example.hpp) + set_property(TARGET rs-flash-logs PROPERTY CXX_STANDARD 11) + target_link_libraries(rs-flash-logs ${DEPENDENCIES}) + include_directories(rs-flash-logs ../ ../../third-party/tclap/include) + set_target_properties (rs-flash-logs PROPERTIES FOLDER "Examples") + + install(TARGETS rs-flash-logs RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}) +endif() diff --git a/examples/flash-logs/rs-flash-logs.cpp b/examples/flash-logs/rs-flash-logs.cpp new file mode 100644 index 0000000000..3658117ad7 --- /dev/null +++ b/examples/flash-logs/rs-flash-logs.cpp @@ -0,0 +1,126 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2017 Intel Corporation. All Rights Reserved. + +#include // Include RealSense Cross Platform API +#include "example.hpp" // Include short list of convenience functions for rendering +#include +#include +#include +#include + +using namespace std; + + +string hexify(unsigned char n) +{ + string res; + + do + { + res += "0123456789ABCDEF"[n % 16]; + n >>= 4; + } while (n); + + reverse(res.begin(), res.end()); + + if (res.size() == 1) + { + res.insert(0, "0"); + } + + return res; +} + +string datetime_string() +{ + auto t = time(nullptr); + char buffer[20] = {}; + const tm* time = localtime(&t); + if (nullptr != time) + strftime(buffer, sizeof(buffer), "%Y-%m-%d %H:%M:%S", time); + + return string(buffer); +} + +// Capture Example demonstrates how to +// capture depth and color video streams and render them to the screen +int main(int argc, char * argv[]) +{ + // Declare RealSense pipeline, encapsulating the actual device and sensors + rs2::pipeline pipe; + + // Start streaming with default recommended configuration + // The default video configuration contains Depth and Color streams + // If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default + auto res = pipe.start(); + + rs2::context ctx; + rs2::device_hub hub(ctx); + + try + { + cout << "\nWaiting for RealSense device to connect...\n"; + auto dev = hub.wait_for_device(); + cout << "RealSense device was connected...\n"; + + setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout + + + auto fw_log = res.get_device().as(); + auto number_of_flash_logs_in_device = fw_log.get_number_of_flash_logs(); + + for (int i = 0; i < number_of_flash_logs_in_device; ++i) + { + auto flash_log_message = fw_log.create_message(); + bool result = fw_log.get_flash_log(flash_log_message); + if (result) + { + std::vector fw_log_lines; + + static bool usingParser = true; + if (usingParser) + { + std::string xml_path("HWLoggerEventsDS5.xml"); + if (!xml_path.empty()) + { + ifstream f(xml_path); + if (f.good()) + { + unique_ptr parser = + unique_ptr(new rs2::firmware_log_parser(xml_path)); + + rs2::firmware_log_parsed_message parsed_log = parser->parse_firmware_log(flash_log_message); + stringstream sstr; + sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() + << " " << parsed_log.thread_name() << " " << parsed_log.file_name() + << " " << parsed_log.line(); + + fw_log_lines.push_back(sstr.str()); + } + } + } + else + { + stringstream sstr; + sstr << flash_log_message.get_timestamp(); + sstr << " " << flash_log_message.get_severity_str(); + sstr << " FW_Log_Data:"; + std::vector msg_data = flash_log_message.data(); + for (int i = 0; i < msg_data.size(); ++i) + { + sstr << hexify(msg_data[i]) << " "; + } + fw_log_lines.push_back(sstr.str()); + } + for (auto& line : fw_log_lines) + cout << line << endl; + } + } + } + catch (const rs2::error & e) + { + cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << endl; + } + + return EXIT_SUCCESS; +} diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index da03320dd3..43f5cd0cfe 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -369,6 +369,18 @@ rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_e * \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor */ int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); + +int rs2_get_number_of_flash_logs(rs2_device* dev, rs2_error** error); + +/** +* \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor +*/ +int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); + /** * Delete RealSense firmware log message * \param[in] device Realsense firmware log message to delete diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index 91c2273510..103a4fadc7 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -444,6 +444,29 @@ namespace rs2 return fw_log_pulling_status; } + + bool get_flash_log(rs2::firmware_log_message& msg) const + { + rs2_error* e = nullptr; + rs2_firmware_log_message* m = msg.get_message().get(); + bool flash_log_pulling_status = + rs2_get_flash_log(_dev.get(), &(m), &e); + + error::handle(e); + + return flash_log_pulling_status; + } + + int get_number_of_flash_logs() const + { + rs2_error* e = nullptr; + int number_of_flash_logs = + rs2_get_number_of_flash_logs(_dev.get(), &e); + + error::handle(e); + + return number_of_flash_logs; + } }; class firmware_log_parsed_message diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index b71e8c4951..fc37f35259 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -9,57 +9,148 @@ namespace librealsense firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, std::string camera_op_code) : _hw_monitor(hardware_monitor), - _message_queue() + _fw_logs_queue(), + _flash_logs_queue() { auto op_code = static_cast(std::stoi(camera_op_code.c_str())); - _input_code = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, - 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; - } + _input_code_for_fw_logs = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, + 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + //TODO - get the right code for flah logs + auto flash_logs_op_code = static_cast(0x09);// static_cast(std::stoi(camera_op_code.c_str())); + //auto flash_logs_offset = { 0x7a, 0x01, 0x00, 0x00 }; + //auto flash_logs_length = { 0xf8, 0x03, 0x00, 0x00 }; + _input_code_for_flash_logs = { 0x14, 0x00, 0xab, 0xcd, flash_logs_op_code, 0x00, 0x00, 0x00, + 0x00, 0xa0, 0x17, 0x00, 0xf8, 0x03, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + } + bool firmware_logger_device::get_fw_log(fw_logs::fw_logs_binary_data& binary_data) { bool result = false; - if (_message_queue.empty()) + if (_fw_logs_queue.empty()) { - get_fw_logs_from_hw_monitor(); + get_logs_from_hw_monitor(LOG_TYPE_FW_LOG); } - if (!_message_queue.empty()) + if (!_fw_logs_queue.empty()) { fw_logs::fw_logs_binary_data data; - data = _message_queue.front(); - _message_queue.pop(); + data = _fw_logs_queue.front(); + _fw_logs_queue.pop(); binary_data = data; result = true; } return result; } - void firmware_logger_device::get_fw_logs_from_hw_monitor() + bool firmware_logger_device::get_flash_log(fw_logs::fw_logs_binary_data& binary_data) { - auto res = _hw_monitor->send(_input_code); + bool result = false; + if (_flash_logs_queue.empty()) + { + get_logs_from_hw_monitor(LOG_TYPE_FLASH_LOG); + } + + if (!_flash_logs_queue.empty()) + { + fw_logs::fw_logs_binary_data data; + data = _flash_logs_queue.front(); + _flash_logs_queue.pop(); + binary_data = data; + result = true; + } + return result; + } + + bool firmware_logger_device::get_log(fw_logs::fw_logs_binary_data& binary_data, log_type type) + { + std::queue* logs_queue; + logs_queue = (type == LOG_TYPE_FW_LOG) ? &_fw_logs_queue : &_flash_logs_queue; + + bool result = false; + if ((*logs_queue).empty()) + { + get_logs_from_hw_monitor(type); + } + + // if log type is fw log --> pop should be done + // if log type is flash log --> no pop should be done (queue pulled only once) + if (!(*logs_queue).empty()) + { + fw_logs::fw_logs_binary_data data; + data = (*logs_queue).front(); + (*logs_queue).pop(); + binary_data = data; + result = true; + } + return result; + } + + bool firmware_logger_device::get_flash_log(fw_logs::fw_logs_binary_data& binary_data) + { + std::queue* logs_queue; + logs_queue = &_flash_logs_queue; + + bool result = false; + if (_flash_logs_queue.empty()) + { + get_logs_from_hw_monitor(LOG_TYPE_FLASH_LOG); + } + + // if log type is fw log --> pop should be done + // if log type is flash log --> no pop should be done (queue pulled only once) + if (!(*logs_queue).empty()) + { + fw_logs::fw_logs_binary_data data; + data = (*logs_queue).front(); + (*logs_queue).pop(); + binary_data = data; + result = true; + } + return result; + } + + // get number N of flash logs - save in object + // user to call get_flash_log N times + // index of vector (not queue) to be saved in fw logger object + // if user calls get_flash_log N+1 times, index to be reset to 0 (cyclic read) + + void firmware_logger_device::get_logs_from_hw_monitor(log_type type) + { + std::queue& logs_queue = (type == LOG_TYPE_FW_LOG) ? _fw_logs_queue : _flash_logs_queue; + const std::vector & input_code = (type == LOG_TYPE_FW_LOG) ? _input_code_for_fw_logs : _input_code_for_flash_logs; + int size_of_header = (type == LOG_TYPE_FW_LOG) ? 4 : 31; + auto res = _hw_monitor->send(input_code); if (res.empty()) { throw std::runtime_error("Getting Firmware logs failed!"); } + int limit = (type == LOG_TYPE_FW_LOG) ? (res.size() - 4) / fw_logs::BINARY_DATA_SIZE : + static_cast(res[0] + (res[1] << 8) + (res[2] << 16) + (res[3] << 24)); + //erasing header - res.erase(res.begin(), res.begin() + 4); + res.erase(res.begin(), res.begin() + size_of_header); auto beginOfLogIterator = res.begin(); // convert bytes to fw_logs_binary_data - for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE; ++i) + for (int i = 0; i < limit; ++i) { + if (*beginOfLogIterator == 0) + break; auto endOfLogIterator = beginOfLogIterator + fw_logs::BINARY_DATA_SIZE; std::vector resultsForOneLog; resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); fw_logs::fw_logs_binary_data binary_data{ resultsForOneLog }; - _message_queue.push(binary_data); + logs_queue.push(binary_data); beginOfLogIterator = endOfLogIterator; } } + int firmware_logger_device::get_number_of_flash_logs() + { - + } } \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 616c62fc32..d05862af2f 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -14,6 +14,7 @@ namespace librealsense { public: virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; + virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual ~firmware_logger_extensions() = default; }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); @@ -26,13 +27,30 @@ namespace librealsense std::string camera_op_code); bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; + bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; + + private: - std::vector _input_code; + enum log_type + { + LOG_TYPE_FW_LOG = 0, + LOG_TYPE_FLASH_LOG = 1, + LOG_TYPE_NUM_OF_TYPES = 2 + }; + + bool get_log(fw_logs::fw_logs_binary_data& binary_data, log_type type); + void get_logs_from_hw_monitor(log_type type); + + std::vector _input_code_for_fw_logs; + std::vector _input_code_for_flash_logs; std::shared_ptr _hw_monitor; - std::queue _message_queue; - void get_fw_logs_from_hw_monitor(); + std::queue _fw_logs_queue; + std::queue _flash_logs_queue; + + + }; } \ No newline at end of file diff --git a/src/fw-logs/fw-logs-parser.h b/src/fw-logs/fw-logs-parser.h index faeb6c5b26..331b35e252 100644 --- a/src/fw-logs/fw-logs-parser.h +++ b/src/fw-logs/fw-logs-parser.h @@ -17,7 +17,7 @@ namespace librealsense explicit fw_logs_parser(std::string xml_full_file_path); ~fw_logs_parser(void); - fw_log_data fw_logs_parser::parse_fw_log(const fw_logs_binary_data* fw_log_msg); + fw_log_data parse_fw_log(const fw_logs_binary_data* fw_log_msg); private: diff --git a/src/realsense.def b/src/realsense.def index 52830ef0cf..617e35d835 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -359,6 +359,7 @@ EXPORTS rs2_create_firmware_log_message rs2_delete_firmware_log_message rs2_get_firmware_log + rs2_get_flash_log rs2_firmware_log_message_severity rs2_firmware_log_message_timestamp rs2_firmware_log_message_data diff --git a/src/rs.cpp b/src/rs.cpp index 9e09c76bdb..068336b985 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -3012,6 +3012,34 @@ int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, } HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg) + +int rs2_get_number_of_flash_logs(rs2_device* dev, rs2_error** error) BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(dev); + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + + fw_logs::fw_logs_binary_data binary_data; + int number_of_flash_logs = fw_loggerable->get_number_of_flash_logs(binary_data); + + return number_of_flash_logs; +} +HANDLE_EXCEPTIONS_AND_RETURN(0, dev) + +int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error)BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(dev); + VALIDATE_NOT_NULL(fw_log_msg); + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + + fw_logs::fw_logs_binary_data binary_data; + bool result = fw_loggerable->get_flash_log(binary_data); + if (result) + { + (*(*fw_log_msg)->firmware_log_binary_data.get()) = binary_data; + } + return result ? 1 : 0; +} +HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg) void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg) BEGIN_API_CALL { VALIDATE_NOT_NULL(msg); From dd69928bd62204d5a08472123cb49065f6cd58c0 Mon Sep 17 00:00:00 2001 From: remibettan Date: Sun, 31 May 2020 21:53:35 +0300 Subject: [PATCH 12/43] fw logs and flash logs implemented --- src/firmware_logger_device.cpp | 164 +++++++++++++++------------------ src/firmware_logger_device.h | 27 +++--- src/realsense.def | 1 + src/rs.cpp | 2 +- 4 files changed, 85 insertions(+), 109 deletions(-) diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index fc37f35259..f28d057f45 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -6,133 +6,88 @@ namespace librealsense { - firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, - std::string camera_op_code) : - _hw_monitor(hardware_monitor), - _fw_logs_queue(), - _flash_logs_queue() - { - auto op_code = static_cast(std::stoi(camera_op_code.c_str())); + firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, + std::string camera_op_code) : + _hw_monitor(hardware_monitor), + _fw_logs(), + _flash_logs(), + _flash_logs_initialized(false), + _flash_logs_index(0) + { + auto op_code = static_cast(std::stoi(camera_op_code.c_str())); _input_code_for_fw_logs = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, - 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; - //TODO - get the right code for flah logs + //TODO - get the right code for flash logs auto flash_logs_op_code = static_cast(0x09);// static_cast(std::stoi(camera_op_code.c_str())); //auto flash_logs_offset = { 0x7a, 0x01, 0x00, 0x00 }; //auto flash_logs_length = { 0xf8, 0x03, 0x00, 0x00 }; - _input_code_for_flash_logs = { 0x14, 0x00, 0xab, 0xcd, flash_logs_op_code, 0x00, 0x00, 0x00, + _input_code_for_flash_logs = { 0x14, 0x00, 0xab, 0xcd, flash_logs_op_code, 0x00, 0x00, 0x00, 0x00, 0xa0, 0x17, 0x00, 0xf8, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; - } - - bool firmware_logger_device::get_fw_log(fw_logs::fw_logs_binary_data& binary_data) - { - bool result = false; - if (_fw_logs_queue.empty()) - { - get_logs_from_hw_monitor(LOG_TYPE_FW_LOG); - } - - if (!_fw_logs_queue.empty()) - { - fw_logs::fw_logs_binary_data data; - data = _fw_logs_queue.front(); - _fw_logs_queue.pop(); - binary_data = data; - result = true; - } - return result; } - bool firmware_logger_device::get_flash_log(fw_logs::fw_logs_binary_data& binary_data) + bool firmware_logger_device::get_fw_log(fw_logs::fw_logs_binary_data& binary_data) { bool result = false; - if (_flash_logs_queue.empty()) + if (_fw_logs.empty()) { - get_logs_from_hw_monitor(LOG_TYPE_FLASH_LOG); + get_fw_logs_from_hw_monitor(); } - if (!_flash_logs_queue.empty()) + if (!_fw_logs.empty()) { fw_logs::fw_logs_binary_data data; - data = _flash_logs_queue.front(); - _flash_logs_queue.pop(); + data = _fw_logs.front(); + _fw_logs.pop(); binary_data = data; result = true; } return result; } - bool firmware_logger_device::get_log(fw_logs::fw_logs_binary_data& binary_data, log_type type) - { - std::queue* logs_queue; - logs_queue = (type == LOG_TYPE_FW_LOG) ? &_fw_logs_queue : &_flash_logs_queue; - - bool result = false; - if ((*logs_queue).empty()) - { - get_logs_from_hw_monitor(type); - } - // if log type is fw log --> pop should be done - // if log type is flash log --> no pop should be done (queue pulled only once) - if (!(*logs_queue).empty()) - { - fw_logs::fw_logs_binary_data data; - data = (*logs_queue).front(); - (*logs_queue).pop(); - binary_data = data; - result = true; - } - return result; - } - - bool firmware_logger_device::get_flash_log(fw_logs::fw_logs_binary_data& binary_data) + void firmware_logger_device::get_fw_logs_from_hw_monitor() { - std::queue* logs_queue; - logs_queue = &_flash_logs_queue; - - bool result = false; - if (_flash_logs_queue.empty()) + int size_of_fw_logs_header = 4; + auto res = _hw_monitor->send(_input_code_for_fw_logs); + if (res.empty()) { - get_logs_from_hw_monitor(LOG_TYPE_FLASH_LOG); + throw std::runtime_error("Getting Firmware logs failed!"); } - // if log type is fw log --> pop should be done - // if log type is flash log --> no pop should be done (queue pulled only once) - if (!(*logs_queue).empty()) + //erasing header + res.erase(res.begin(), res.begin() + size_of_fw_logs_header); + + auto beginOfLogIterator = res.begin(); + // convert bytes to fw_logs_binary_data + for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE; ++i) { - fw_logs::fw_logs_binary_data data; - data = (*logs_queue).front(); - (*logs_queue).pop(); - binary_data = data; - result = true; + if (*beginOfLogIterator == 0) + break; + auto endOfLogIterator = beginOfLogIterator + fw_logs::BINARY_DATA_SIZE; + std::vector resultsForOneLog; + resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); + fw_logs::fw_logs_binary_data binary_data{ resultsForOneLog }; + _fw_logs.push(binary_data); + beginOfLogIterator = endOfLogIterator; } - return result; } - // get number N of flash logs - save in object - // user to call get_flash_log N times - // index of vector (not queue) to be saved in fw logger object - // if user calls get_flash_log N+1 times, index to be reset to 0 (cyclic read) - - void firmware_logger_device::get_logs_from_hw_monitor(log_type type) + void firmware_logger_device::get_flash_logs_from_hw_monitor() { - std::queue& logs_queue = (type == LOG_TYPE_FW_LOG) ? _fw_logs_queue : _flash_logs_queue; - const std::vector & input_code = (type == LOG_TYPE_FW_LOG) ? _input_code_for_fw_logs : _input_code_for_flash_logs; - int size_of_header = (type == LOG_TYPE_FW_LOG) ? 4 : 31; - auto res = _hw_monitor->send(input_code); + int size_of_flash_logs_header = 31; + auto res = _hw_monitor->send(_input_code_for_flash_logs); if (res.empty()) { - throw std::runtime_error("Getting Firmware logs failed!"); + throw std::runtime_error("Getting Flash logs failed!"); } - int limit = (type == LOG_TYPE_FW_LOG) ? (res.size() - 4) / fw_logs::BINARY_DATA_SIZE : - static_cast(res[0] + (res[1] << 8) + (res[2] << 16) + (res[3] << 24)); - + int limit = static_cast(res[0] + (res[1] << 8) + (res[2] << 16) + (res[3] << 24)); + //erasing header - res.erase(res.begin(), res.begin() + size_of_header); + res.erase(res.begin(), res.begin() + size_of_flash_logs_header); auto beginOfLogIterator = res.begin(); // convert bytes to fw_logs_binary_data @@ -144,13 +99,38 @@ namespace librealsense std::vector resultsForOneLog; resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); fw_logs::fw_logs_binary_data binary_data{ resultsForOneLog }; - logs_queue.push(binary_data); + _flash_logs.push_back(binary_data); beginOfLogIterator = endOfLogIterator; } + + _flash_logs_initialized = true; } - int firmware_logger_device::get_number_of_flash_logs() + bool firmware_logger_device::get_flash_log(fw_logs::fw_logs_binary_data& binary_data) { + bool result = false; + if (!_flash_logs_initialized) + { + get_flash_logs_from_hw_monitor(); + } + + if (!_flash_logs.empty()) + { + fw_logs::fw_logs_binary_data data; + data = _flash_logs[_flash_logs_index]; + _flash_logs_index = (_flash_logs_index + 1) % (_flash_logs.size()); + binary_data = data; + result = true; + } + return result; + } + size_t firmware_logger_device::get_number_of_flash_logs() + { + if (!_flash_logs_initialized) + { + get_flash_logs_from_hw_monitor(); + } + return _flash_logs.size(); } } \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index d05862af2f..12f54c7de2 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -15,11 +15,12 @@ namespace librealsense public: virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; + virtual size_t get_number_of_flash_logs() = 0; virtual ~firmware_logger_extensions() = default; }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); - + class firmware_logger_device : public virtual device, public firmware_logger_extensions { public: @@ -29,28 +30,22 @@ namespace librealsense bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; - + size_t get_number_of_flash_logs() override; private: - enum log_type - { - LOG_TYPE_FW_LOG = 0, - LOG_TYPE_FLASH_LOG = 1, - LOG_TYPE_NUM_OF_TYPES = 2 - }; + void get_fw_logs_from_hw_monitor(); + void get_flash_logs_from_hw_monitor(); - bool get_log(fw_logs::fw_logs_binary_data& binary_data, log_type type); - void get_logs_from_hw_monitor(log_type type); - - std::vector _input_code_for_fw_logs; - std::vector _input_code_for_flash_logs; std::shared_ptr _hw_monitor; - std::queue _fw_logs_queue; - std::queue _flash_logs_queue; - + std::queue _fw_logs; + std::vector _flash_logs; + bool _flash_logs_initialized; + int _flash_logs_index; + std::vector _input_code_for_fw_logs; + std::vector _input_code_for_flash_logs; }; } \ No newline at end of file diff --git a/src/realsense.def b/src/realsense.def index 617e35d835..baa64c8ebb 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -360,6 +360,7 @@ EXPORTS rs2_delete_firmware_log_message rs2_get_firmware_log rs2_get_flash_log + rs2_get_number_of_flash_logs rs2_firmware_log_message_severity rs2_firmware_log_message_timestamp rs2_firmware_log_message_data diff --git a/src/rs.cpp b/src/rs.cpp index 068336b985..5160882761 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -3019,7 +3019,7 @@ int rs2_get_number_of_flash_logs(rs2_device* dev, rs2_error** error) BEGIN_API_C auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); fw_logs::fw_logs_binary_data binary_data; - int number_of_flash_logs = fw_loggerable->get_number_of_flash_logs(binary_data); + int number_of_flash_logs = fw_loggerable->get_number_of_flash_logs(); return number_of_flash_logs; } From 25863282b841f1dd7e6ecbb45d24a1a459269625 Mon Sep 17 00:00:00 2001 From: remibettan Date: Tue, 2 Jun 2020 12:17:54 +0300 Subject: [PATCH 13/43] Parser made member of fw_logger, need to solve case for parsing without init --- examples/firmware-logs/rs-firmware-logs.cpp | 12 +- include/librealsense2/h/rs_device.h | 20 +-- include/librealsense2/hpp/rs_device.hpp | 134 +++++++++----------- src/firmware_logger_device.cpp | 18 ++- src/firmware_logger_device.h | 8 ++ src/realsense.def | 3 +- src/rs.cpp | 29 ++--- 7 files changed, 109 insertions(+), 115 deletions(-) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index bc4cb22c4a..1da5678c6d 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -68,9 +68,9 @@ int main(int argc, char * argv[]) while (hub.is_connected(dev)) { - auto fw_log = res.get_device().as(); - auto fw_log_message = fw_log.create_message(); - bool result = fw_log.get_firmware_log(fw_log_message); + auto fw_log_device = res.get_device().as(); + auto fw_log_message = fw_log_device.create_message(); + bool result = fw_log_device.get_firmware_log(fw_log_message); if (result) { std::vector fw_log_lines; @@ -84,10 +84,8 @@ int main(int argc, char * argv[]) ifstream f(xml_path); if (f.good()) { - unique_ptr parser = - unique_ptr(new rs2::firmware_log_parser(xml_path)); - - rs2::firmware_log_parsed_message parsed_log = parser->parse_firmware_log(fw_log_message); + bool parser_initialized = fw_log_device.init_parser(xml_path); + rs2::firmware_log_parsed_message parsed_log = fw_log_device.parse_log(fw_log_message); stringstream sstr; sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() << " " << parsed_log.thread_name() << " " << parsed_log.file_name() diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index 43f5cd0cfe..731120ca86 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -421,28 +421,22 @@ unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, r rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); /** -* \brief Creates RealSense firmware logs parser. +* \brief Initializes RealSense firmware logs parser in device. +* \param[in] dev Device from which the FW log will be taken * \param[in] xml_path path to xml file needed for parsing -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return firmware logs parser object -*/ -rs2_firmware_log_parser* rs2_create_firmware_log_parser(const char* xml_path, rs2_error** error); - -/** -* \brief Frees the relevant firmware logs parser object. -* \param[in] firmware logs parser object that is no longer needed +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails */ -void rs2_delete_firmware_log_parser(rs2_firmware_log_parser* parser); +int rs2_init_parser(rs2_device* dev, const char* xml_path, rs2_error** error); /** * \brief Gets RealSense firmware log parser -* \param[in] fw_logs_parser firmware log parser +* \param[in] dev Device from which the FW log will be taken * \param[in] fw_log_msg firmware log message to be parsed * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return firmware log parsed message */ -rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_firmware_log_parser* fw_logs_parser, - rs2_firmware_log_message* fw_log_msg, rs2_error** error); +rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error); /** * Delete RealSense firmware log parsed message diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index 103a4fadc7..e07efbe4d7 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -408,6 +408,59 @@ namespace rs2 std::shared_ptr _fw_log_message; }; + class firmware_log_parsed_message + { + public: + explicit firmware_log_parsed_message(std::shared_ptr msg) : + _parsed_fw_log(msg) {} + + std::string message() const + { + rs2_error* e = nullptr; + std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e)); + error::handle(e); + return msg; + } + std::string file_name() const + { + rs2_error* e = nullptr; + std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return file_name; + } + std::string thread_name() const + { + rs2_error* e = nullptr; + std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return thread_name; + } + std::string severity() const + { + rs2_error* e = nullptr; + rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e); + error::handle(e); + return std::string(rs2_log_severity_to_string(sev)); + } + uint32_t line() const + { + rs2_error* e = nullptr; + uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e)); + error::handle(e); + return line; + } + uint32_t timestamp() const + { + rs2_error* e = nullptr; + uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e)); + error::handle(e); + return timestamp; + } + + private: + std::shared_ptr _parsed_fw_log; + }; + class firmware_logger : public device { public: @@ -467,98 +520,31 @@ namespace rs2 return number_of_flash_logs; } - }; - class firmware_log_parsed_message - { - public: - explicit firmware_log_parsed_message(std::shared_ptr msg) : - _parsed_fw_log(msg) {} - - std::string message() const - { - rs2_error* e = nullptr; - std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e)); - error::handle(e); - return msg; - } - std::string file_name() const - { - rs2_error* e = nullptr; - std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e)); - error::handle(e); - return file_name; - } - std::string thread_name() const - { - rs2_error* e = nullptr; - std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e)); - error::handle(e); - return thread_name; - } - std::string severity() const - { - rs2_error* e = nullptr; - rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e); - error::handle(e); - return std::string(rs2_log_severity_to_string(sev)); - } - uint32_t line() const + bool init_parser(const std::string& xml_path) { rs2_error* e = nullptr; - uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e)); - error::handle(e); - return line; - } - uint32_t timestamp() const - { - rs2_error* e = nullptr; - uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e)); - error::handle(e); - return timestamp; - } - - private: - std::shared_ptr _parsed_fw_log; - }; - - class firmware_log_parser - { - public: - firmware_log_parser(std::string xml_path) - { - rs2_error* e = nullptr; - _firmware_log_parser = std::shared_ptr( - rs2_create_firmware_log_parser(xml_path.data(), &e), - rs2_delete_firmware_log_parser); + bool parser_initialized = rs2_init_parser(_dev.get(), xml_path.c_str(), &e); error::handle(e); + + return parser_initialized; } - rs2::firmware_log_parsed_message parse_firmware_log(const rs2::firmware_log_message& msg) + rs2::firmware_log_parsed_message parse_log(const rs2::firmware_log_message& msg) { rs2_error* e = nullptr; - auto size = rs2_firmware_log_message_size(msg.get_message().get(), &e); - error::handle(e); - std::shared_ptr parsed_msg( - rs2_parse_firmware_log(_firmware_log_parser.get(), msg.get_message().get(), &e), + rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), &e), rs2_delete_firmware_log_parsed_message); error::handle(e); return firmware_log_parsed_message(parsed_msg); } - - firmware_log_parser(std::shared_ptr fw_log_parser) - : _firmware_log_parser(fw_log_parser) {} - - explicit operator std::shared_ptr() { return _firmware_log_parser; }; - - protected: - std::shared_ptr _firmware_log_parser; }; + class auto_calibrated_device : public calibrated_device { public: diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index f28d057f45..997b1a9fbf 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -12,7 +12,8 @@ namespace librealsense _fw_logs(), _flash_logs(), _flash_logs_initialized(false), - _flash_logs_index(0) + _flash_logs_index(0), + _parser(nullptr) { auto op_code = static_cast(std::stoi(camera_op_code.c_str())); _input_code_for_fw_logs = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, @@ -133,4 +134,19 @@ namespace librealsense } return _flash_logs.size(); } + + bool firmware_logger_device::init_parser(std::string xml_full_file_path) + { + _parser = new fw_logs::fw_logs_parser(xml_full_file_path); + + return (_parser != nullptr); + } + + fw_logs::fw_log_data firmware_logger_device::parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg) + { + fw_logs::fw_log_data log_data; + if(_parser) + log_data = _parser->parse_fw_log(fw_log_msg); + return log_data; + } } \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 12f54c7de2..4fb59f33fa 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -7,6 +7,7 @@ #include "device.h" #include #include "fw-logs/fw-log-data.h" +#include "fw-logs/fw-logs-parser.h" namespace librealsense { @@ -15,6 +16,8 @@ namespace librealsense public: virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; + virtual bool init_parser(std::string xml_full_file_path) = 0; + virtual fw_logs::fw_log_data parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg) = 0; virtual size_t get_number_of_flash_logs() = 0; virtual ~firmware_logger_extensions() = default; }; @@ -30,6 +33,9 @@ namespace librealsense bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; + bool init_parser(std::string xml_full_file_path) override; + fw_logs::fw_log_data parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg) override; + size_t get_number_of_flash_logs() override; private: @@ -46,6 +52,8 @@ namespace librealsense std::vector _input_code_for_fw_logs; std::vector _input_code_for_flash_logs; + + fw_logs::fw_logs_parser* _parser; }; } \ No newline at end of file diff --git a/src/realsense.def b/src/realsense.def index baa64c8ebb..bd7ae915a1 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -365,8 +365,7 @@ EXPORTS rs2_firmware_log_message_timestamp rs2_firmware_log_message_data rs2_firmware_log_message_size - rs2_create_firmware_log_parser - rs2_delete_firmware_log_parser + rs2_init_parser rs2_parse_firmware_log rs2_delete_firmware_log_parsed_message rs2_get_fw_log_parsed_message diff --git a/src/rs.cpp b/src/rs.cpp index 5160882761..e37fa7e22a 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -132,10 +132,6 @@ struct rs2_firmware_log_parsed_message std::shared_ptr firmware_log_parsed; }; -struct rs2_firmware_log_parser -{ - std::shared_ptr firmware_log_parser; -}; struct rs2_error { @@ -3074,32 +3070,29 @@ unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, r } HANDLE_EXCEPTIONS_AND_RETURN(0, msg) -rs2_firmware_log_parser* rs2_create_firmware_log_parser(const char* xml_path, rs2_error** error) BEGIN_API_CALL +int rs2_init_parser(rs2_device* dev, const char* xml_path ,rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_path); + + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - return new rs2_firmware_log_parser{ std::make_shared(xml_path)}; -} -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, xml_path) - -void rs2_delete_firmware_log_parser(rs2_firmware_log_parser* parser) BEGIN_API_CALL -{ - VALIDATE_NOT_NULL(parser); - delete parser; + return (fw_loggerable->init_parser(xml_path)) ? 1 : 0; } -NOEXCEPT_RETURN(, parser) +HANDLE_EXCEPTIONS_AND_RETURN(0, xml_path) -rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_firmware_log_parser* fw_log_parser, rs2_firmware_log_message* fw_log_msg, rs2_error** error) BEGIN_API_CALL +rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error) BEGIN_API_CALL { - VALIDATE_NOT_NULL(fw_log_parser); + VALIDATE_NOT_NULL(dev); VALIDATE_NOT_NULL(fw_log_msg); + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + librealsense::fw_logs::fw_log_data log_data = - fw_log_parser->firmware_log_parser.get()->parse_fw_log(fw_log_msg->firmware_log_binary_data.get()); + fw_loggerable->parse_log(fw_log_msg->firmware_log_binary_data.get()); return new rs2_firmware_log_parsed_message{ std::make_shared(log_data) }; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, fw_log_msg) +HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, fw_log_msg) void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg) BEGIN_API_CALL { From c2f47de1b182bbe5080f0b211fed7f03637e5af9 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 3 Jun 2020 09:01:51 +0300 Subject: [PATCH 14/43] rs-fw-logger tool using new API --- examples/CMakeLists.txt | 1 - examples/firmware-logs/rs-firmware-logs.cpp | 43 +++++----- tools/fw-logger/CMakeLists.txt | 11 +-- tools/fw-logger/rs-fw-logger.cpp | 87 ++++++++++----------- 4 files changed, 65 insertions(+), 77 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 8f1a688f36..59e516c697 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -47,5 +47,4 @@ add_subdirectory(ar-basic) add_subdirectory(ar-advanced) add_subdirectory(pose-apriltag) add_subdirectory(tracking-and-depth) -add_subdirectory(firmware-logs) add_subdirectory(flash-logs) diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp index 1da5678c6d..50c2bb6cbe 100644 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ b/examples/firmware-logs/rs-firmware-logs.cpp @@ -66,34 +66,37 @@ int main(int argc, char * argv[]) setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout + auto fw_log_device = res.get_device().as(); + + bool using_parser = false; + std::string xml_path("C:\\Users\\rbettan\\Documents\\Dev\\RefFolder\\HWLoggerEventsDS5.xml"); + if (!xml_path.empty()) + { + ifstream f(xml_path); + if (f.good()) + { + bool parser_initialized = fw_log_device.init_parser(xml_path); + if (parser_initialized) + using_parser = true; + } + } + while (hub.is_connected(dev)) { - auto fw_log_device = res.get_device().as(); auto fw_log_message = fw_log_device.create_message(); bool result = fw_log_device.get_firmware_log(fw_log_message); if (result) { std::vector fw_log_lines; - - static bool usingParser = true; - if (usingParser) + if (using_parser) { - std::string xml_path("HWLoggerEventsDS5.xml"); - if (!xml_path.empty()) - { - ifstream f(xml_path); - if (f.good()) - { - bool parser_initialized = fw_log_device.init_parser(xml_path); - rs2::firmware_log_parsed_message parsed_log = fw_log_device.parse_log(fw_log_message); - stringstream sstr; - sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() - << " " << parsed_log.thread_name() << " " << parsed_log.file_name() - << " " << parsed_log.line(); - - fw_log_lines.push_back(sstr.str()); - } - } + rs2::firmware_log_parsed_message parsed_log = fw_log_device.parse_log(fw_log_message); + stringstream sstr; + sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() + << " " << parsed_log.thread_name() << " " << parsed_log.file_name() + << " " << parsed_log.line(); + + fw_log_lines.push_back(sstr.str()); } else { diff --git a/tools/fw-logger/CMakeLists.txt b/tools/fw-logger/CMakeLists.txt index 77dc526328..094c2645c2 100644 --- a/tools/fw-logger/CMakeLists.txt +++ b/tools/fw-logger/CMakeLists.txt @@ -5,16 +5,7 @@ cmake_minimum_required(VERSION 3.1.0) project(RealsenseToolsFirmwareLogger) -add_executable(rs-fw-logger rs-fw-logger.cpp fw-log-data.cpp - fw-log-data.h - fw-logs-formating-options.cpp - fw-logs-formating-options.h - fw-logs-parser.cpp - fw-logs-parser.h - fw-logs-xml-helper.cpp - fw-logs-xml-helper.h - string-formatter.cpp - string-formatter.h) +add_executable(rs-fw-logger rs-fw-logger.cpp fw-log-data.cpp) set_property(TARGET rs-fw-logger PROPERTY CXX_STANDARD 11) if(WIN32 OR ANDROID) target_link_libraries(rs-fw-logger ${DEPENDENCIES}) diff --git a/tools/fw-logger/rs-fw-logger.cpp b/tools/fw-logger/rs-fw-logger.cpp index 432b26dcd0..ed5afbfa0b 100644 --- a/tools/fw-logger/rs-fw-logger.cpp +++ b/tools/fw-logger/rs-fw-logger.cpp @@ -5,13 +5,11 @@ #include #include #include "tclap/CmdLine.h" -#include "fw-logs-parser.h" using namespace std; using namespace TCLAP; -using namespace fw_logger; using namespace rs2; string char2hex(unsigned char n) @@ -53,20 +51,9 @@ int main(int argc, char* argv[]) cmd.parse(argc, argv); log_to_file(RS2_LOG_SEVERITY_WARN, "librealsense.log"); - // Obtain a list of devices currently present on the system - unique_ptr fw_log_parser; auto use_xml_file = false; auto xml_full_file_path = xml_arg.getValue(); - if (!xml_full_file_path.empty()) - { - ifstream f(xml_full_file_path); - if (f.good()) - { - fw_log_parser = unique_ptr(new fw_logs_parser(xml_full_file_path)); - use_xml_file = true; - } - } context ctx; device_hub hub(ctx); @@ -79,47 +66,55 @@ int main(int argc, char* argv[]) auto dev = hub.wait_for_device(); cout << "RealSense device was connected...\n"; - vector input; - auto str_op_code = dev.get_info(RS2_CAMERA_INFO_DEBUG_OP_CODE); - auto op_code = static_cast(stoi(str_op_code)); - input = {0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, - 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}; - - cout << "Device Name: " << dev.get_info(RS2_CAMERA_INFO_NAME) << endl << - "Device Location: " << dev.get_info(RS2_CAMERA_INFO_PHYSICAL_PORT) << endl << endl; - setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout - while (hub.is_connected(dev)) - { - this_thread::sleep_for(chrono::milliseconds(100)); - - auto raw_data = dev.as().send_and_receive_raw_data(input); - vector fw_log_lines = {""}; - if (raw_data.size() <= 4) - continue; + auto fw_log_device = dev.as(); - if (use_xml_file) + bool using_parser = false; + if (!xml_full_file_path.empty()) + { + ifstream f(xml_full_file_path); + if (f.good()) { - fw_logs_binary_data fw_logs_binary_data = {raw_data}; - fw_logs_binary_data.logs_buffer.erase(fw_logs_binary_data.logs_buffer.begin(),fw_logs_binary_data.logs_buffer.begin()+4); - fw_log_lines = fw_log_parser->get_fw_log_lines(fw_logs_binary_data); - for (auto& elem : fw_log_lines) - elem = datetime_string() + " " + elem; + bool parser_initialized = fw_log_device.init_parser(xml_full_file_path); + if (parser_initialized) + using_parser = true; } - else + } + + while (hub.is_connected(dev)) + { + auto fw_log_message = fw_log_device.create_message(); + bool result = fw_log_device.get_firmware_log(fw_log_message); + if (result) { - stringstream sstr; - sstr << datetime_string() << " FW_Log_Data:"; - for (size_t i = 0; i < raw_data.size(); ++i) + std::vector fw_log_lines; + if (using_parser) + { + rs2::firmware_log_parsed_message parsed_log = fw_log_device.parse_log(fw_log_message); + stringstream sstr; + sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() + << " " << parsed_log.thread_name() << " " << parsed_log.file_name() + << " " << parsed_log.line(); + + fw_log_lines.push_back(sstr.str()); + } + else + { + stringstream sstr; + sstr << fw_log_message.get_timestamp(); + sstr << " " << fw_log_message.get_severity_str(); + sstr << " FW_Log_Data:"; + std::vector msg_data = fw_log_message.data(); + for (int i = 0; i < msg_data.size(); ++i) + { sstr << char2hex(raw_data[i]) << " "; - - fw_log_lines.push_back(sstr.str()); + } + fw_log_lines.push_back(sstr.str()); + } + for (auto& line : fw_log_lines) + cout << line << endl; } - - for (auto& line : fw_log_lines) - cout << line << endl; } } catch (const error & e) From 91e53b51e74ca486c27551e9b2c4c7d4f5b41107 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 3 Jun 2020 12:01:11 +0300 Subject: [PATCH 15/43] fw logs api functions moved to dedicated header files --- include/CMakeLists.txt | 6 +- include/librealsense2/h/rs_device.h | 139 ----------- include/librealsense2/h/rs_firmware_logs.h | 160 ++++++++++++ include/librealsense2/hpp/rs_device.hpp | 233 ------------------ .../librealsense2/hpp/rs_firmware_logs.hpp | 204 +++++++++++++++ include/librealsense2/rs.h | 1 + include/librealsense2/rs.hpp | 1 + src/rs.cpp | 1 - tools/fw-logger/CMakeLists.txt | 2 +- 9 files changed, 371 insertions(+), 376 deletions(-) create mode 100644 include/librealsense2/h/rs_firmware_logs.h create mode 100644 include/librealsense2/hpp/rs_firmware_logs.hpp diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 9ace5a5d02..46fcaed190 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -16,7 +16,8 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_internal.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_pipeline.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_config.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_terminal_parser.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_firmware_logs.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_terminal_parser.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_types.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_context.hpp" @@ -30,7 +31,8 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_options.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_internal.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_pipeline.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_terminal_parser.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_firmware_logs.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_terminal_parser.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rsutil.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs_advanced_mode.h" diff --git a/include/librealsense2/h/rs_device.h b/include/librealsense2/h/rs_device.h index 731120ca86..43ba91b8d3 100644 --- a/include/librealsense2/h/rs_device.h +++ b/include/librealsense2/h/rs_device.h @@ -353,145 +353,6 @@ rs2_raw_data_buffer* rs2_serialize_json(rs2_device* dev, rs2_error** error); /* Load JSON and apply advanced-mode controls */ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_size, rs2_error** error); -/** -* \brief Creates RealSense firmware log message. -* \param[in] dev Device from which the FW log will be taken using the created message -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return pointer to created empty firmware log message -*/ -rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_error** error); - -/** -* \brief Gets RealSense firmware log. -* \param[in] dev Device from which the FW log should be taken -* \param[in] fw_log_msg Firmware log message object to be filled -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor -*/ -int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); - -int rs2_get_number_of_flash_logs(rs2_device* dev, rs2_error** error); - -/** -* \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device -* \param[in] dev Device from which the FW log should be taken -* \param[in] fw_log_msg Firmware log message object to be filled -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor -*/ -int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); - -/** -* Delete RealSense firmware log message -* \param[in] device Realsense firmware log message to delete -*/ -void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg); - -/** -* \brief Gets RealSense firmware log message data. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return pointer to start of the firmware log message data -*/ -const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log message size. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return size of the firmware log message data -*/ -int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); - - -/** -* \brief Gets RealSense firmware log message timestamp. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return timestamp of the firmware log message -*/ -unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log message severity. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return severity of the firmware log message data -*/ -rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); - -/** -* \brief Initializes RealSense firmware logs parser in device. -* \param[in] dev Device from which the FW log will be taken -* \param[in] xml_path path to xml file needed for parsing -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails -*/ -int rs2_init_parser(rs2_device* dev, const char* xml_path, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parser -* \param[in] dev Device from which the FW log will be taken -* \param[in] fw_log_msg firmware log message to be parsed -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return firmware log parsed message -*/ -rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error); - -/** -* Delete RealSense firmware log parsed message -* \param[in] device Realsense firmware log parsed message to delete -*/ -void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); - -/** -* \brief Gets RealSense firmware log parsed message message. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return message of the firmware log parsed message -*/ -const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message file name. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return file name of the firmware log parsed message -*/ -const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message thread name. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return thread name of the firmware log parsed message -*/ -const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message severity. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return severity of the firmware log parsed message -*/ -rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_log_parsed_file_name). -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return line number of the firmware log parsed message -*/ -unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message timestamp -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return timestamp of the firmware log parsed message -*/ -unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - #ifdef __cplusplus } #endif diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h new file mode 100644 index 0000000000..79dbe72333 --- /dev/null +++ b/include/librealsense2/h/rs_firmware_logs.h @@ -0,0 +1,160 @@ +/* License: Apache 2.0. See LICENSE file in root directory. + Copyright(c) 2020 Intel Corporation. All Rights Reserved. */ + +/** \file rs_firmware_logs.h +* \brief Exposes RealSense firmware logs functionality for C compilers +*/ + + +#ifndef LIBREALSENSE_RS2_FIRMWARE_LOGS_H +#define LIBREALSENSE_RS2_FIRMWARE_LOGS_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include "rs_types.h" + +/** +* \brief Creates RealSense firmware log message. +* \param[in] dev Device from which the FW log will be taken using the created message +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to created empty firmware log message +*/ +rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_error** error); + +/** +* \brief Gets RealSense firmware log. +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor +*/ +int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); + +int rs2_get_number_of_flash_logs(rs2_device* dev, rs2_error** error); + +/** +* \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor +*/ +int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); + +/** +* Delete RealSense firmware log message +* \param[in] device Realsense firmware log message to delete +*/ +void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg); + +/** +* \brief Gets RealSense firmware log message data. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to start of the firmware log message data +*/ +const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log message size. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return size of the firmware log message data +*/ +int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); + + +/** +* \brief Gets RealSense firmware log message timestamp. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return timestamp of the firmware log message +*/ +unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log message severity. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return severity of the firmware log message data +*/ +rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Initializes RealSense firmware logs parser in device. +* \param[in] dev Device from which the FW log will be taken +* \param[in] xml_path path to xml file needed for parsing +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails +*/ +int rs2_init_parser(rs2_device* dev, const char* xml_path, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parser +* \param[in] dev Device from which the FW log will be taken +* \param[in] fw_log_msg firmware log message to be parsed +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return firmware log parsed message +*/ +rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error); + +/** +* Delete RealSense firmware log parsed message +* \param[in] device Realsense firmware log parsed message to delete +*/ +void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); + +/** +* \brief Gets RealSense firmware log parsed message message. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return message of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message file name. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return file name of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message thread name. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return thread name of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message severity. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return severity of the firmware log parsed message +*/ +rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_log_parsed_file_name). +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return line number of the firmware log parsed message +*/ +unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message timestamp +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return timestamp of the firmware log parsed message +*/ +unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +#ifdef __cplusplus +} +#endif +#endif diff --git a/include/librealsense2/hpp/rs_device.hpp b/include/librealsense2/hpp/rs_device.hpp index e07efbe4d7..bab9808827 100644 --- a/include/librealsense2/hpp/rs_device.hpp +++ b/include/librealsense2/hpp/rs_device.hpp @@ -312,239 +312,6 @@ namespace rs2 } }; - class firmware_logs_helper - { - public: - static uint32_t build_uint32_from4_uint8(const uint8_t* start) - { - uint8_t first = *(start); - uint8_t second = (*(start + 1)); - uint8_t third = (*(start + 2)); - uint8_t fourth = (*(start + 3)); - uint32_t res = first; - res += static_cast(second << 8); - res += static_cast(third << 16); - res += static_cast(fourth << 24); - return res; - } - - static double build_double_from8_uint8(const uint8_t* start) - { - uint64_t resInInt = build_uint64_from8_uint8(start); - double res = *reinterpret_cast(&resInInt); - return res; - } - - static uint64_t build_uint64_from8_uint8(const uint8_t* start) - { - uint32_t first = build_uint32_from4_uint8(start); - start += 4; - uint32_t second = build_uint32_from4_uint8(start); - uint64_t res = first; - res += static_cast(second << 32); - - return res; - } - - static std::string build_string_from_uint8_and_size(const uint8_t* start, uint8_t size) - { - std::string res; - res.insert(res.begin(), start, start + size); - return res; - } - }; - - - class firmware_log_message - { - public: - explicit firmware_log_message(std::shared_ptr msg): - _fw_log_message(msg){} - - rs2_log_severity get_severity() const { - rs2_error* e = nullptr; - rs2_log_severity severity = rs2_firmware_log_message_severity(_fw_log_message.get(), &e); - error::handle(e); - return severity; - } - std::string get_severity_str() const { - return rs2_log_severity_to_string(get_severity()); - } - - uint32_t get_timestamp() const - { - rs2_error* e = nullptr; - uint32_t timestamp = rs2_firmware_log_message_timestamp(_fw_log_message.get(), &e); - error::handle(e); - return timestamp; - } - - int size() const - { - rs2_error* e = nullptr; - int size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); - error::handle(e); - return size; - } - - std::vector data() const - { - rs2_error* e = nullptr; - auto size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); - error::handle(e); - std::vector result; - if (size > 0) - { - auto start = rs2_firmware_log_message_data(_fw_log_message.get(), &e); - error::handle(e); - result.insert(result.begin(), start, start + size); - } - return result; - } - - const std::shared_ptr get_message() const { return _fw_log_message; } - - private: - std::shared_ptr _fw_log_message; - }; - - class firmware_log_parsed_message - { - public: - explicit firmware_log_parsed_message(std::shared_ptr msg) : - _parsed_fw_log(msg) {} - - std::string message() const - { - rs2_error* e = nullptr; - std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e)); - error::handle(e); - return msg; - } - std::string file_name() const - { - rs2_error* e = nullptr; - std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e)); - error::handle(e); - return file_name; - } - std::string thread_name() const - { - rs2_error* e = nullptr; - std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e)); - error::handle(e); - return thread_name; - } - std::string severity() const - { - rs2_error* e = nullptr; - rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e); - error::handle(e); - return std::string(rs2_log_severity_to_string(sev)); - } - uint32_t line() const - { - rs2_error* e = nullptr; - uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e)); - error::handle(e); - return line; - } - uint32_t timestamp() const - { - rs2_error* e = nullptr; - uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e)); - error::handle(e); - return timestamp; - } - - private: - std::shared_ptr _parsed_fw_log; - }; - - class firmware_logger : public device - { - public: - firmware_logger(device d) - : device(d.get()) - { - rs2_error* e = nullptr; - if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_FW_LOGGER, &e) == 0 && !e) - { - _dev.reset(); - } - error::handle(e); - } - - rs2::firmware_log_message create_message() - { - rs2_error* e = nullptr; - std::shared_ptr msg( - rs2_create_firmware_log_message(_dev.get(), &e), - rs2_delete_firmware_log_message); - error::handle(e); - - return firmware_log_message(msg); - } - - bool get_firmware_log(rs2::firmware_log_message& msg) const - { - rs2_error* e = nullptr; - rs2_firmware_log_message* m = msg.get_message().get(); - bool fw_log_pulling_status = - rs2_get_firmware_log(_dev.get(), &(m), &e); - - error::handle(e); - - return fw_log_pulling_status; - } - - bool get_flash_log(rs2::firmware_log_message& msg) const - { - rs2_error* e = nullptr; - rs2_firmware_log_message* m = msg.get_message().get(); - bool flash_log_pulling_status = - rs2_get_flash_log(_dev.get(), &(m), &e); - - error::handle(e); - - return flash_log_pulling_status; - } - - int get_number_of_flash_logs() const - { - rs2_error* e = nullptr; - int number_of_flash_logs = - rs2_get_number_of_flash_logs(_dev.get(), &e); - - error::handle(e); - - return number_of_flash_logs; - } - - bool init_parser(const std::string& xml_path) - { - rs2_error* e = nullptr; - - bool parser_initialized = rs2_init_parser(_dev.get(), xml_path.c_str(), &e); - error::handle(e); - - return parser_initialized; - } - - rs2::firmware_log_parsed_message parse_log(const rs2::firmware_log_message& msg) - { - rs2_error* e = nullptr; - - std::shared_ptr parsed_msg( - rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), &e), - rs2_delete_firmware_log_parsed_message); - error::handle(e); - - return firmware_log_parsed_message(parsed_msg); - } - }; - - class auto_calibrated_device : public calibrated_device { public: diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp new file mode 100644 index 0000000000..9e34bd6dbd --- /dev/null +++ b/include/librealsense2/hpp/rs_firmware_logs.hpp @@ -0,0 +1,204 @@ +// License: Apache 2.0. See LICENSE file in root directory. +// Copyright(c) 2020 Intel Corporation. All Rights Reserved. + +#ifndef LIBREALSENSE_RS2_FIRMWARE_LOGS_HPP +#define LIBREALSENSE_RS2_FIRMWARE_LOGS_HPP + +#include "rs_types.hpp" +#include "rs_sensor.hpp" +#include "../h/rs_firmware_logs.h" +#include + +namespace rs2 +{ + class firmware_log_message + { + public: + explicit firmware_log_message(std::shared_ptr msg): + _fw_log_message(msg){} + + rs2_log_severity get_severity() const { + rs2_error* e = nullptr; + rs2_log_severity severity = rs2_firmware_log_message_severity(_fw_log_message.get(), &e); + error::handle(e); + return severity; + } + std::string get_severity_str() const { + return rs2_log_severity_to_string(get_severity()); + } + + uint32_t get_timestamp() const + { + rs2_error* e = nullptr; + uint32_t timestamp = rs2_firmware_log_message_timestamp(_fw_log_message.get(), &e); + error::handle(e); + return timestamp; + } + + int size() const + { + rs2_error* e = nullptr; + int size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); + error::handle(e); + return size; + } + + std::vector data() const + { + rs2_error* e = nullptr; + auto size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); + error::handle(e); + std::vector result; + if (size > 0) + { + auto start = rs2_firmware_log_message_data(_fw_log_message.get(), &e); + error::handle(e); + result.insert(result.begin(), start, start + size); + } + return result; + } + + const std::shared_ptr get_message() const { return _fw_log_message; } + + private: + std::shared_ptr _fw_log_message; + }; + + class firmware_log_parsed_message + { + public: + explicit firmware_log_parsed_message(std::shared_ptr msg) : + _parsed_fw_log(msg) {} + + std::string message() const + { + rs2_error* e = nullptr; + std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e)); + error::handle(e); + return msg; + } + std::string file_name() const + { + rs2_error* e = nullptr; + std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return file_name; + } + std::string thread_name() const + { + rs2_error* e = nullptr; + std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return thread_name; + } + std::string severity() const + { + rs2_error* e = nullptr; + rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e); + error::handle(e); + return std::string(rs2_log_severity_to_string(sev)); + } + uint32_t line() const + { + rs2_error* e = nullptr; + uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e)); + error::handle(e); + return line; + } + uint32_t timestamp() const + { + rs2_error* e = nullptr; + uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e)); + error::handle(e); + return timestamp; + } + + private: + std::shared_ptr _parsed_fw_log; + }; + + class firmware_logger : public device + { + public: + firmware_logger(device d) + : device(d.get()) + { + rs2_error* e = nullptr; + if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_FW_LOGGER, &e) == 0 && !e) + { + _dev.reset(); + } + error::handle(e); + } + + rs2::firmware_log_message create_message() + { + rs2_error* e = nullptr; + std::shared_ptr msg( + rs2_create_firmware_log_message(_dev.get(), &e), + rs2_delete_firmware_log_message); + error::handle(e); + + return firmware_log_message(msg); + } + + bool get_firmware_log(rs2::firmware_log_message& msg) const + { + rs2_error* e = nullptr; + rs2_firmware_log_message* m = msg.get_message().get(); + bool fw_log_pulling_status = + rs2_get_firmware_log(_dev.get(), &(m), &e); + + error::handle(e); + + return fw_log_pulling_status; + } + + bool get_flash_log(rs2::firmware_log_message& msg) const + { + rs2_error* e = nullptr; + rs2_firmware_log_message* m = msg.get_message().get(); + bool flash_log_pulling_status = + rs2_get_flash_log(_dev.get(), &(m), &e); + + error::handle(e); + + return flash_log_pulling_status; + } + + int get_number_of_flash_logs() const + { + rs2_error* e = nullptr; + int number_of_flash_logs = + rs2_get_number_of_flash_logs(_dev.get(), &e); + + error::handle(e); + + return number_of_flash_logs; + } + + bool init_parser(const std::string& xml_path) + { + rs2_error* e = nullptr; + + bool parser_initialized = rs2_init_parser(_dev.get(), xml_path.c_str(), &e); + error::handle(e); + + return parser_initialized; + } + + rs2::firmware_log_parsed_message parse_log(const rs2::firmware_log_message& msg) + { + rs2_error* e = nullptr; + + std::shared_ptr parsed_msg( + rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), &e), + rs2_delete_firmware_log_parsed_message); + error::handle(e); + + return firmware_log_parsed_message(parsed_msg); + } + }; + +} +#endif // LIBREALSENSE_RS2_FIRMWARE_LOGS_HPP diff --git a/include/librealsense2/rs.h b/include/librealsense2/rs.h index f43e816461..dfb29974d8 100644 --- a/include/librealsense2/rs.h +++ b/include/librealsense2/rs.h @@ -21,6 +21,7 @@ extern "C" { #include "h/rs_processing.h" #include "h/rs_record_playback.h" #include "h/rs_sensor.h" +#include "h/rs_firmware_logs.h" #include "h/rs_terminal_parser.h" #define RS2_API_MAJOR_VERSION 2 diff --git a/include/librealsense2/rs.hpp b/include/librealsense2/rs.hpp index e23f167b76..b41366102d 100644 --- a/include/librealsense2/rs.hpp +++ b/include/librealsense2/rs.hpp @@ -13,6 +13,7 @@ #include "hpp/rs_record_playback.hpp" #include "hpp/rs_sensor.hpp" #include "hpp/rs_pipeline.hpp" +#include "hpp/rs_firmware_logs.hpp" #include "hpp/rs_terminal_parser.hpp" namespace rs2 diff --git a/src/rs.cpp b/src/rs.cpp index e37fa7e22a..b30aee0aca 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -43,7 +43,6 @@ #include "auto-calibrated-device.h" #include "terminal-parser.h" #include "firmware_logger_device.h" -#include "fw-logs/fw-logs-parser.h" //////////////////////// // API implementation // //////////////////////// diff --git a/tools/fw-logger/CMakeLists.txt b/tools/fw-logger/CMakeLists.txt index 094c2645c2..8a762ca87b 100644 --- a/tools/fw-logger/CMakeLists.txt +++ b/tools/fw-logger/CMakeLists.txt @@ -5,7 +5,7 @@ cmake_minimum_required(VERSION 3.1.0) project(RealsenseToolsFirmwareLogger) -add_executable(rs-fw-logger rs-fw-logger.cpp fw-log-data.cpp) +add_executable(rs-fw-logger rs-fw-logger.cpp) set_property(TARGET rs-fw-logger PROPERTY CXX_STANDARD 11) if(WIN32 OR ANDROID) target_link_libraries(rs-fw-logger ${DEPENDENCIES}) From 0a6982740f402d1e098fa38f26332ce25e1fb5d6 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 3 Jun 2020 12:46:36 +0300 Subject: [PATCH 16/43] parse_log api change so that boolean value would be returned --- include/librealsense2/h/rs_firmware_logs.h | 21 +++++++++++++++++-- .../librealsense2/hpp/rs_firmware_logs.hpp | 21 ++++++++++++++----- src/firmware_logger_device.cpp | 15 ++++++++----- src/firmware_logger_device.h | 4 ++-- src/realsense.def | 1 + src/rs.cpp | 21 ++++++++++++++----- tools/fw-logger/rs-fw-logger.cpp | 4 +++- 7 files changed, 67 insertions(+), 20 deletions(-) diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h index 79dbe72333..184b81e996 100644 --- a/include/librealsense2/h/rs_firmware_logs.h +++ b/include/librealsense2/h/rs_firmware_logs.h @@ -91,14 +91,31 @@ rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_messag */ int rs2_init_parser(rs2_device* dev, const char* xml_path, rs2_error** error); + +/** +* \brief Creates RealSense firmware log parsed message. +* \param[in] dev Device from which the FW log will be taken using the created message +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to created empty firmware log message +*/ +rs2_firmware_log_parsed_message* rs2_create_firmware_log_parsed_message(rs2_device* dev, rs2_error** error); + +/** +* \brief Deletes RealSense firmware log parsed message. +* \param[in] msg message to be deleted +*/ +void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); + + /** * \brief Gets RealSense firmware log parser * \param[in] dev Device from which the FW log will be taken * \param[in] fw_log_msg firmware log message to be parsed +* \param[in] parsed_msg firmware log parsed message - place holder for the resulting parsed message * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return firmware log parsed message +* \return true for success, false for failure - failure happens if message could not be parsed */ -rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error); +int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_firmware_log_parsed_message* parsed_msg, rs2_error** error); /** * Delete RealSense firmware log parsed message diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp index 9e34bd6dbd..0e2815b50e 100644 --- a/include/librealsense2/hpp/rs_firmware_logs.hpp +++ b/include/librealsense2/hpp/rs_firmware_logs.hpp @@ -113,6 +113,8 @@ namespace rs2 return timestamp; } + const std::shared_ptr get_message() const { return _parsed_fw_log; } + private: std::shared_ptr _parsed_fw_log; }; @@ -142,6 +144,17 @@ namespace rs2 return firmware_log_message(msg); } + rs2::firmware_log_parsed_message create_parsed_message() + { + rs2_error* e = nullptr; + std::shared_ptr msg( + rs2_create_firmware_log_parsed_message(_dev.get(), &e), + rs2_delete_firmware_log_parsed_message); + error::handle(e); + + return firmware_log_parsed_message(msg); + } + bool get_firmware_log(rs2::firmware_log_message& msg) const { rs2_error* e = nullptr; @@ -187,16 +200,14 @@ namespace rs2 return parser_initialized; } - rs2::firmware_log_parsed_message parse_log(const rs2::firmware_log_message& msg) + bool parse_log(const rs2::firmware_log_message& msg, const rs2::firmware_log_parsed_message& parsed_msg) { rs2_error* e = nullptr; - std::shared_ptr parsed_msg( - rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), &e), - rs2_delete_firmware_log_parsed_message); + bool parsingResult = rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), parsed_msg.get_message().get(), &e); error::handle(e); - return firmware_log_parsed_message(parsed_msg); + return parsingResult; } }; diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 997b1a9fbf..8424ebf0dc 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -142,11 +142,16 @@ namespace librealsense return (_parser != nullptr); } - fw_logs::fw_log_data firmware_logger_device::parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg) + bool firmware_logger_device::parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, + fw_logs::fw_log_data* parsed_msg) { - fw_logs::fw_log_data log_data; - if(_parser) - log_data = _parser->parse_fw_log(fw_log_msg); - return log_data; + bool result = false; + if (_parser && parsed_msg && fw_log_msg) + { + *parsed_msg = _parser->parse_fw_log(fw_log_msg); + result = true; + } + + return result; } } \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 4fb59f33fa..f2b428bf8e 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -17,7 +17,7 @@ namespace librealsense virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual bool init_parser(std::string xml_full_file_path) = 0; - virtual fw_logs::fw_log_data parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg) = 0; + virtual bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) = 0; virtual size_t get_number_of_flash_logs() = 0; virtual ~firmware_logger_extensions() = default; }; @@ -34,7 +34,7 @@ namespace librealsense bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; bool init_parser(std::string xml_full_file_path) override; - fw_logs::fw_log_data parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg) override; + bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; size_t get_number_of_flash_logs() override; diff --git a/src/realsense.def b/src/realsense.def index bd7ae915a1..83b0a9e939 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -367,6 +367,7 @@ EXPORTS rs2_firmware_log_message_size rs2_init_parser rs2_parse_firmware_log + rs2_create_firmware_log_parsed_message rs2_delete_firmware_log_parsed_message rs2_get_fw_log_parsed_message rs2_get_fw_log_parsed_file_name diff --git a/src/rs.cpp b/src/rs.cpp index b30aee0aca..923e789046 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -3079,19 +3079,30 @@ int rs2_init_parser(rs2_device* dev, const char* xml_path ,rs2_error** error) BE } HANDLE_EXCEPTIONS_AND_RETURN(0, xml_path) -rs2_firmware_log_parsed_message* rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_error** error) BEGIN_API_CALL +rs2_firmware_log_parsed_message* rs2_create_firmware_log_parsed_message(rs2_device* dev, rs2_error** error)BEGIN_API_CALL +{ + VALIDATE_NOT_NULL(dev); + + auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); + + return new rs2_firmware_log_parsed_message{ std::make_shared () }; +} +HANDLE_EXCEPTIONS_AND_RETURN(0, dev) + +int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_firmware_log_parsed_message* parsed_msg, rs2_error** error)BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); VALIDATE_NOT_NULL(fw_log_msg); + VALIDATE_NOT_NULL(parsed_msg); auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - librealsense::fw_logs::fw_log_data log_data = - fw_loggerable->parse_log(fw_log_msg->firmware_log_binary_data.get()); + bool parsing_result = fw_loggerable->parse_log(fw_log_msg->firmware_log_binary_data.get(), + parsed_msg->firmware_log_parsed.get()); - return new rs2_firmware_log_parsed_message{ std::make_shared(log_data) }; + return parsing_result ? 1 : 0; } -HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev, fw_log_msg) +HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg) void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg) BEGIN_API_CALL { diff --git a/tools/fw-logger/rs-fw-logger.cpp b/tools/fw-logger/rs-fw-logger.cpp index ed5afbfa0b..aadf665e52 100644 --- a/tools/fw-logger/rs-fw-logger.cpp +++ b/tools/fw-logger/rs-fw-logger.cpp @@ -91,7 +91,9 @@ int main(int argc, char* argv[]) std::vector fw_log_lines; if (using_parser) { - rs2::firmware_log_parsed_message parsed_log = fw_log_device.parse_log(fw_log_message); + auto parsed_log = fw_log_device.create_parsed_message(); + bool parsing_result = fw_log_device.parse_log(fw_log_message, parsed_log); + stringstream sstr; sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() << " " << parsed_log.thread_name() << " " << parsed_log.file_name() From c8bbb536d4fe234d9f871122b1dbb52ddc9d5db4 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 3 Jun 2020 13:13:05 +0300 Subject: [PATCH 17/43] correct flash log example - to be deleted ater on --- examples/flash-logs/rs-flash-logs.cpp | 50 +++++++++++++++------------ 1 file changed, 28 insertions(+), 22 deletions(-) diff --git a/examples/flash-logs/rs-flash-logs.cpp b/examples/flash-logs/rs-flash-logs.cpp index 3658117ad7..e25e44b33e 100644 --- a/examples/flash-logs/rs-flash-logs.cpp +++ b/examples/flash-logs/rs-flash-logs.cpp @@ -66,13 +66,26 @@ int main(int argc, char * argv[]) setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout - auto fw_log = res.get_device().as(); - auto number_of_flash_logs_in_device = fw_log.get_number_of_flash_logs(); + auto fw_log_device = res.get_device().as(); + auto number_of_flash_logs_in_device = fw_log_device.get_number_of_flash_logs(); + + bool using_parser = false; + std::string xml_full_file_path("HWLoggerEventsDS5.xml"); + if (!xml_full_file_path.empty()) + { + ifstream f(xml_full_file_path); + if (f.good()) + { + bool parser_initialized = fw_log_device.init_parser(xml_full_file_path); + if (parser_initialized) + using_parser = true; + } + } for (int i = 0; i < number_of_flash_logs_in_device; ++i) { - auto flash_log_message = fw_log.create_message(); - bool result = fw_log.get_flash_log(flash_log_message); + auto flash_log_message = fw_log_device.create_message(); + bool result = fw_log_device.get_flash_log(flash_log_message); if (result) { std::vector fw_log_lines; @@ -80,24 +93,17 @@ int main(int argc, char * argv[]) static bool usingParser = true; if (usingParser) { - std::string xml_path("HWLoggerEventsDS5.xml"); - if (!xml_path.empty()) - { - ifstream f(xml_path); - if (f.good()) - { - unique_ptr parser = - unique_ptr(new rs2::firmware_log_parser(xml_path)); - - rs2::firmware_log_parsed_message parsed_log = parser->parse_firmware_log(flash_log_message); - stringstream sstr; - sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() - << " " << parsed_log.thread_name() << " " << parsed_log.file_name() - << " " << parsed_log.line(); - - fw_log_lines.push_back(sstr.str()); - } - } + + auto parsed_log = fw_log_device.create_parsed_message(); + bool parsing_result = fw_log_device.parse_log(flash_log_message, parsed_log); + + stringstream sstr; + sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() + << " " << parsed_log.thread_name() << " " << parsed_log.file_name() + << " " << parsed_log.line(); + + fw_log_lines.push_back(sstr.str()); + } else { From 85887216e5057a59846157d3ddbc0a248e16421b Mon Sep 17 00:00:00 2001 From: remibettan Date: Tue, 9 Jun 2020 13:03:23 +0300 Subject: [PATCH 18/43] flash logs pulling coorected to be same as fw logs --- examples/flash-logs/rs-flash-logs.cpp | 8 ++++++-- include/librealsense2/h/rs_firmware_logs.h | 2 -- include/librealsense2/hpp/rs_firmware_logs.hpp | 11 ----------- src/firmware_logger_device.cpp | 16 +++------------- src/firmware_logger_device.h | 6 +----- src/realsense.def | 1 - src/rs.cpp | 13 ------------- 7 files changed, 10 insertions(+), 47 deletions(-) diff --git a/examples/flash-logs/rs-flash-logs.cpp b/examples/flash-logs/rs-flash-logs.cpp index e25e44b33e..04b9b2569e 100644 --- a/examples/flash-logs/rs-flash-logs.cpp +++ b/examples/flash-logs/rs-flash-logs.cpp @@ -67,7 +67,6 @@ int main(int argc, char * argv[]) auto fw_log_device = res.get_device().as(); - auto number_of_flash_logs_in_device = fw_log_device.get_number_of_flash_logs(); bool using_parser = false; std::string xml_full_file_path("HWLoggerEventsDS5.xml"); @@ -82,7 +81,8 @@ int main(int argc, char * argv[]) } } - for (int i = 0; i < number_of_flash_logs_in_device; ++i) + bool flash_logs_to_pull = true; + while (hub.is_connected(dev) && flash_logs_to_pull) { auto flash_log_message = fw_log_device.create_message(); bool result = fw_log_device.get_flash_log(flash_log_message); @@ -121,6 +121,10 @@ int main(int argc, char * argv[]) for (auto& line : fw_log_lines) cout << line << endl; } + else + { + flash_logs_to_pull = false; + } } } catch (const rs2::error & e) diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h index 184b81e996..3a17c57c6b 100644 --- a/include/librealsense2/h/rs_firmware_logs.h +++ b/include/librealsense2/h/rs_firmware_logs.h @@ -32,8 +32,6 @@ rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_e */ int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); -int rs2_get_number_of_flash_logs(rs2_device* dev, rs2_error** error); - /** * \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device * \param[in] dev Device from which the FW log should be taken diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp index 0e2815b50e..c9fdadafca 100644 --- a/include/librealsense2/hpp/rs_firmware_logs.hpp +++ b/include/librealsense2/hpp/rs_firmware_logs.hpp @@ -179,17 +179,6 @@ namespace rs2 return flash_log_pulling_status; } - int get_number_of_flash_logs() const - { - rs2_error* e = nullptr; - int number_of_flash_logs = - rs2_get_number_of_flash_logs(_dev.get(), &e); - - error::handle(e); - - return number_of_flash_logs; - } - bool init_parser(const std::string& xml_path) { rs2_error* e = nullptr; diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 8424ebf0dc..1a13c0d91b 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -12,7 +12,6 @@ namespace librealsense _fw_logs(), _flash_logs(), _flash_logs_initialized(false), - _flash_logs_index(0), _parser(nullptr) { auto op_code = static_cast(std::stoi(camera_op_code.c_str())); @@ -100,7 +99,7 @@ namespace librealsense std::vector resultsForOneLog; resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); fw_logs::fw_logs_binary_data binary_data{ resultsForOneLog }; - _flash_logs.push_back(binary_data); + _flash_logs.push(binary_data); beginOfLogIterator = endOfLogIterator; } @@ -118,23 +117,14 @@ namespace librealsense if (!_flash_logs.empty()) { fw_logs::fw_logs_binary_data data; - data = _flash_logs[_flash_logs_index]; - _flash_logs_index = (_flash_logs_index + 1) % (_flash_logs.size()); + data = _flash_logs.front(); + _flash_logs.pop(); binary_data = data; result = true; } return result; } - size_t firmware_logger_device::get_number_of_flash_logs() - { - if (!_flash_logs_initialized) - { - get_flash_logs_from_hw_monitor(); - } - return _flash_logs.size(); - } - bool firmware_logger_device::init_parser(std::string xml_full_file_path) { _parser = new fw_logs::fw_logs_parser(xml_full_file_path); diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index f2b428bf8e..a3eaa507ae 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -18,7 +18,6 @@ namespace librealsense virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual bool init_parser(std::string xml_full_file_path) = 0; virtual bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) = 0; - virtual size_t get_number_of_flash_logs() = 0; virtual ~firmware_logger_extensions() = default; }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); @@ -36,8 +35,6 @@ namespace librealsense bool init_parser(std::string xml_full_file_path) override; bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; - size_t get_number_of_flash_logs() override; - private: void get_fw_logs_from_hw_monitor(); void get_flash_logs_from_hw_monitor(); @@ -45,10 +42,9 @@ namespace librealsense std::shared_ptr _hw_monitor; std::queue _fw_logs; - std::vector _flash_logs; + std::queue _flash_logs; bool _flash_logs_initialized; - int _flash_logs_index; std::vector _input_code_for_fw_logs; std::vector _input_code_for_flash_logs; diff --git a/src/realsense.def b/src/realsense.def index 83b0a9e939..d013030882 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -360,7 +360,6 @@ EXPORTS rs2_delete_firmware_log_message rs2_get_firmware_log rs2_get_flash_log - rs2_get_number_of_flash_logs rs2_firmware_log_message_severity rs2_firmware_log_message_timestamp rs2_firmware_log_message_data diff --git a/src/rs.cpp b/src/rs.cpp index 923e789046..320650286c 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -3007,19 +3007,6 @@ int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, } HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg) - -int rs2_get_number_of_flash_logs(rs2_device* dev, rs2_error** error) BEGIN_API_CALL -{ - VALIDATE_NOT_NULL(dev); - auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - - fw_logs::fw_logs_binary_data binary_data; - int number_of_flash_logs = fw_loggerable->get_number_of_flash_logs(); - - return number_of_flash_logs; -} -HANDLE_EXCEPTIONS_AND_RETURN(0, dev) - int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error)BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); From a8b9b7f45528768972a205b3763d98575c2d4afc Mon Sep 17 00:00:00 2001 From: remibettan Date: Mon, 15 Jun 2020 15:19:14 +0300 Subject: [PATCH 19/43] fw logger extension added to the ds5 devices, opcode removed from ctor --- src/ds5/ds5-factory.cpp | 120 ++++++++++++++++++++++----------- src/firmware_logger_device.cpp | 12 +--- src/firmware_logger_device.h | 3 +- 3 files changed, 85 insertions(+), 50 deletions(-) diff --git a/src/ds5/ds5-factory.cpp b/src/ds5/ds5-factory.cpp index 1923da4ede..6d63e88708 100644 --- a/src/ds5/ds5-factory.cpp +++ b/src/ds5/ds5-factory.cpp @@ -27,7 +27,9 @@ namespace librealsense { // PSR - class rs400_device : public ds5_nonmonochrome, public ds5_advanced_mode_base + class rs400_device : public ds5_nonmonochrome, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs400_device(std::shared_ptr ctx, @@ -36,7 +38,8 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5_device(ctx, group), ds5_nonmonochrome(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -62,7 +65,8 @@ namespace librealsense // DS5U_S class rs405u_device : public ds5u_device, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs405u_device(std::shared_ptr ctx, @@ -70,7 +74,8 @@ namespace librealsense bool register_device_notifications) : device(ctx, group, register_device_notifications), ds5u_device(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -109,7 +114,9 @@ namespace librealsense // ASR (D460) class rs410_device : public ds5_nonmonochrome, - public ds5_active, public ds5_advanced_mode_base + public ds5_active, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs410_device(std::shared_ptr ctx, @@ -119,7 +126,8 @@ namespace librealsense ds5_device(ctx, group), ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -144,7 +152,8 @@ namespace librealsense class rs415_device : public ds5_nonmonochrome, public ds5_active, public ds5_color, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs415_device(std::shared_ptr ctx, @@ -155,7 +164,8 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_color(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -180,7 +190,9 @@ namespace librealsense }; class rs416_device : public ds5_nonmonochrome, - public ds5_active, public ds5_advanced_mode_base + public ds5_active, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs416_device(std::shared_ptr ctx, @@ -190,7 +202,8 @@ namespace librealsense ds5_device(ctx, group), ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -229,7 +242,8 @@ namespace librealsense public ds5_nonmonochrome, public ds5_active, public ds5_color, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: @@ -241,7 +255,8 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_color(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -279,7 +294,9 @@ namespace librealsense }; // PWGT - class rs420_mm_device : public ds5_motion, public ds5_advanced_mode_base + class rs420_mm_device : public ds5_motion, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs420_mm_device(std::shared_ptr ctx, @@ -288,7 +305,8 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5_device(ctx, group), ds5_motion(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -321,7 +339,9 @@ namespace librealsense }; // PWG - class rs420_device : public ds5_device, public ds5_advanced_mode_base + class rs420_device : public ds5_device, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs420_device(std::shared_ptr ctx, @@ -329,7 +349,8 @@ namespace librealsense bool register_device_notifications) : device(ctx, group, register_device_notifications), ds5_device(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -354,7 +375,9 @@ namespace librealsense }; // AWG - class rs430_device : public ds5_active, public ds5_advanced_mode_base + class rs430_device : public ds5_active, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs430_device(std::shared_ptr ctx, @@ -363,7 +386,8 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5_device(ctx, group), ds5_active(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -387,7 +411,10 @@ namespace librealsense }; }; - class rs430i_device : public ds5_active, public ds5_advanced_mode_base, public ds5_motion + class rs430i_device : public ds5_active, + public ds5_advanced_mode_base, + public ds5_motion, + public firmware_logger_device { public: rs430i_device(std::shared_ptr ctx, @@ -397,7 +424,8 @@ namespace librealsense ds5_device(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - ds5_motion(ctx, group) + ds5_motion(ctx, group), + firmware_logger_device(ds5_device::_hw_monitor) {} std::vector get_profiles_tags() const override @@ -427,7 +455,8 @@ namespace librealsense // AWGT class rs430_mm_device : public ds5_active, public ds5_motion, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs430_mm_device(std::shared_ptr ctx, @@ -437,7 +466,8 @@ namespace librealsense ds5_device(ctx, group), ds5_active(ctx, group), ds5_motion(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -485,7 +515,7 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor().get_info(RS2_CAMERA_INFO_DEBUG_OP_CODE)) {} + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -513,7 +543,8 @@ namespace librealsense class rs430_rgb_mm_device : public ds5_active, public ds5_color, public ds5_motion, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs430_rgb_mm_device(std::shared_ptr ctx, @@ -524,7 +555,8 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_motion(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -552,7 +584,8 @@ namespace librealsense class rs435i_device : public ds5_active, public ds5_color, public ds5_motion, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs435i_device(std::shared_ptr ctx, @@ -563,7 +596,8 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_motion(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) { check_and_restore_rgb_stream_extrinsic(); } @@ -767,7 +801,8 @@ namespace librealsense public ds5_nonmonochrome, public ds5_color, public ds5_motion, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs465_device(std::shared_ptr ctx, @@ -779,7 +814,8 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_nonmonochrome(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -804,7 +840,8 @@ namespace librealsense }; class rs400_imu_device : public ds5_motion, - public ds5_advanced_mode_base + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs400_imu_device(std::shared_ptr ctx, @@ -813,7 +850,8 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5_device(ctx, group), ds5_motion(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) {} + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -828,9 +866,10 @@ namespace librealsense }; class rs405_device : public ds5_active, - public ds5_color, - public ds5_motion, - public ds5_advanced_mode_base + public ds5_color, + public ds5_motion, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs405_device(std::shared_ptr ctx, @@ -841,7 +880,8 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_motion(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -871,9 +911,10 @@ namespace librealsense }; class rs455_device : public ds5_active, - public ds5_color, - public ds5_motion, - public ds5_advanced_mode_base + public ds5_color, + public ds5_motion, + public ds5_advanced_mode_base, + public firmware_logger_device { public: rs455_device(std::shared_ptr ctx, @@ -884,7 +925,8 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_motion(ctx, group), - ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()) + ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(ds5_device::_hw_monitor) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 1a13c0d91b..3be27f70b6 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -6,24 +6,18 @@ namespace librealsense { - firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, - std::string camera_op_code) : + firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor) : _hw_monitor(hardware_monitor), _fw_logs(), _flash_logs(), _flash_logs_initialized(false), _parser(nullptr) { - auto op_code = static_cast(std::stoi(camera_op_code.c_str())); - _input_code_for_fw_logs = { 0x14, 0x00, 0xab, 0xcd, op_code, 0x00, 0x00, 0x00, + _input_code_for_fw_logs = { 0x14, 0x00, 0xab, 0xcd, 0x0f, 0x00, 0x00, 0x00, 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; - //TODO - get the right code for flash logs - auto flash_logs_op_code = static_cast(0x09);// static_cast(std::stoi(camera_op_code.c_str())); - //auto flash_logs_offset = { 0x7a, 0x01, 0x00, 0x00 }; - //auto flash_logs_length = { 0xf8, 0x03, 0x00, 0x00 }; - _input_code_for_flash_logs = { 0x14, 0x00, 0xab, 0xcd, flash_logs_op_code, 0x00, 0x00, 0x00, + _input_code_for_flash_logs = { 0x14, 0x00, 0xab, 0xcd, 0x09, 0x00, 0x00, 0x00, 0x00, 0xa0, 0x17, 0x00, 0xf8, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; } diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index a3eaa507ae..a250a3b933 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -26,8 +26,7 @@ namespace librealsense class firmware_logger_device : public virtual device, public firmware_logger_extensions { public: - firmware_logger_device(std::shared_ptr hardware_monitor, - std::string camera_op_code); + firmware_logger_device(std::shared_ptr hardware_monitor); bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; From 0b146894bd3e5941134232d729c5943158fb2476 Mon Sep 17 00:00:00 2001 From: remibettan Date: Mon, 15 Jun 2020 15:54:28 +0300 Subject: [PATCH 20/43] xml content sent to api instead of xml path --- examples/flash-logs/rs-flash-logs.cpp | 3 ++- include/librealsense2/h/rs_firmware_logs.h | 10 +++++----- include/librealsense2/hpp/rs_firmware_logs.hpp | 4 ++-- src/firmware_logger_device.cpp | 4 ++-- src/firmware_logger_device.h | 4 ++-- src/fw-logs/fw-logs-formating-options.cpp | 6 +++--- src/fw-logs/fw-logs-formating-options.h | 4 ++-- src/fw-logs/fw-logs-parser.cpp | 4 ++-- src/fw-logs/fw-logs-parser.h | 2 +- src/fw-logs/fw-logs-xml-helper.cpp | 16 +++++++--------- src/fw-logs/fw-logs-xml-helper.h | 4 ++-- src/rs.cpp | 8 ++++---- tools/fw-logger/rs-fw-logger.cpp | 3 ++- 13 files changed, 36 insertions(+), 36 deletions(-) diff --git a/examples/flash-logs/rs-flash-logs.cpp b/examples/flash-logs/rs-flash-logs.cpp index 04b9b2569e..25c5d45aa4 100644 --- a/examples/flash-logs/rs-flash-logs.cpp +++ b/examples/flash-logs/rs-flash-logs.cpp @@ -75,7 +75,8 @@ int main(int argc, char * argv[]) ifstream f(xml_full_file_path); if (f.good()) { - bool parser_initialized = fw_log_device.init_parser(xml_full_file_path); + std::string xml_content((std::istreambuf_iterator(f)), std::istreambuf_iterator()); + bool parser_initialized = fw_log_device.init_parser(xml_content); if (parser_initialized) using_parser = true; } diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h index 3a17c57c6b..6d1aa71dee 100644 --- a/include/librealsense2/h/rs_firmware_logs.h +++ b/include/librealsense2/h/rs_firmware_logs.h @@ -82,12 +82,12 @@ rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_messag /** * \brief Initializes RealSense firmware logs parser in device. -* \param[in] dev Device from which the FW log will be taken -* \param[in] xml_path path to xml file needed for parsing -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails +* \param[in] dev Device from which the FW log will be taken +* \param[in] xml_content content of the xml file needed for parsing +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails */ -int rs2_init_parser(rs2_device* dev, const char* xml_path, rs2_error** error); +int rs2_init_parser(rs2_device* dev, const char* xml_content, rs2_error** error); /** diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp index c9fdadafca..c80f68ee45 100644 --- a/include/librealsense2/hpp/rs_firmware_logs.hpp +++ b/include/librealsense2/hpp/rs_firmware_logs.hpp @@ -179,11 +179,11 @@ namespace rs2 return flash_log_pulling_status; } - bool init_parser(const std::string& xml_path) + bool init_parser(const std::string& xml_content) { rs2_error* e = nullptr; - bool parser_initialized = rs2_init_parser(_dev.get(), xml_path.c_str(), &e); + bool parser_initialized = rs2_init_parser(_dev.get(), xml_content.c_str(), &e); error::handle(e); return parser_initialized; diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 3be27f70b6..05f45d52aa 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -119,9 +119,9 @@ namespace librealsense return result; } - bool firmware_logger_device::init_parser(std::string xml_full_file_path) + bool firmware_logger_device::init_parser(std::string xml_content) { - _parser = new fw_logs::fw_logs_parser(xml_full_file_path); + _parser = new fw_logs::fw_logs_parser(xml_content); return (_parser != nullptr); } diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index a250a3b933..d8b8a4a75f 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -16,7 +16,7 @@ namespace librealsense public: virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; - virtual bool init_parser(std::string xml_full_file_path) = 0; + virtual bool init_parser(std::string xml_content) = 0; virtual bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) = 0; virtual ~firmware_logger_extensions() = default; }; @@ -31,7 +31,7 @@ namespace librealsense bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; - bool init_parser(std::string xml_full_file_path) override; + bool init_parser(std::string xml_content) override; bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; private: diff --git a/src/fw-logs/fw-logs-formating-options.cpp b/src/fw-logs/fw-logs-formating-options.cpp index 1bab57c1af..0b8a947ac1 100644 --- a/src/fw-logs/fw-logs-formating-options.cpp +++ b/src/fw-logs/fw-logs-formating-options.cpp @@ -21,8 +21,8 @@ namespace librealsense {} - fw_logs_formating_options::fw_logs_formating_options(const string& xml_full_file_path) - : _xml_full_file_path(xml_full_file_path) + fw_logs_formating_options::fw_logs_formating_options(const string& xml_content) + : _xml_content(xml_content) {} @@ -87,7 +87,7 @@ namespace librealsense bool fw_logs_formating_options::initialize_from_xml() { - fw_logs_xml_helper fw_logs_xml(_xml_full_file_path); + fw_logs_xml_helper fw_logs_xml(_xml_content); return fw_logs_xml.build_log_meta_data(this); } } diff --git a/src/fw-logs/fw-logs-formating-options.h b/src/fw-logs/fw-logs-formating-options.h index 241f92496f..3578fcbee0 100644 --- a/src/fw-logs/fw-logs-formating-options.h +++ b/src/fw-logs/fw-logs-formating-options.h @@ -31,7 +31,7 @@ namespace librealsense class fw_logs_formating_options { public: - fw_logs_formating_options(const std::string& xml_full_file_path); + fw_logs_formating_options(const std::string& xml_content); ~fw_logs_formating_options(void); @@ -48,7 +48,7 @@ namespace librealsense std::unordered_map _fw_logs_thread_names_list; std::unordered_map>> _fw_logs_enum_names_list; - std::string _xml_full_file_path; + std::string _xml_content; }; } } diff --git a/src/fw-logs/fw-logs-parser.cpp b/src/fw-logs/fw-logs-parser.cpp index 7e57f6579f..bd76b1d87e 100644 --- a/src/fw-logs/fw-logs-parser.cpp +++ b/src/fw-logs/fw-logs-parser.cpp @@ -12,8 +12,8 @@ namespace librealsense { namespace fw_logs { - fw_logs_parser::fw_logs_parser(string xml_full_file_path) - : _fw_logs_formating_options(xml_full_file_path), + fw_logs_parser::fw_logs_parser(string xml_content) + : _fw_logs_formating_options(xml_content), _last_timestamp(0), _timestamp_factor(0.00001) { diff --git a/src/fw-logs/fw-logs-parser.h b/src/fw-logs/fw-logs-parser.h index 331b35e252..a06af30718 100644 --- a/src/fw-logs/fw-logs-parser.h +++ b/src/fw-logs/fw-logs-parser.h @@ -14,7 +14,7 @@ namespace librealsense class fw_logs_parser : public std::enable_shared_from_this { public: - explicit fw_logs_parser(std::string xml_full_file_path); + explicit fw_logs_parser(std::string xml_content); ~fw_logs_parser(void); fw_log_data parse_fw_log(const fw_logs_binary_data* fw_log_msg); diff --git a/src/fw-logs/fw-logs-xml-helper.cpp b/src/fw-logs/fw-logs-xml-helper.cpp index 03132f65b1..42adfd501d 100644 --- a/src/fw-logs/fw-logs-xml-helper.cpp +++ b/src/fw-logs/fw-logs-xml-helper.cpp @@ -12,9 +12,9 @@ namespace librealsense { namespace fw_logs { - fw_logs_xml_helper::fw_logs_xml_helper(string xml_full_file_path) + fw_logs_xml_helper::fw_logs_xml_helper(string xml_content) : _init_done(false), - _xml_full_file_path(xml_full_file_path) + _xml_content(xml_content) {} @@ -38,15 +38,13 @@ namespace librealsense { try { - if (_xml_full_file_path.empty()) + if (_xml_content.empty()) return false; - rapidxml::file<> xml_file(_xml_full_file_path.c_str()); - - _document_buffer.resize(xml_file.size() + 2); - memcpy(_document_buffer.data(), xml_file.data(), xml_file.size()); - _document_buffer[xml_file.size()] = '\0'; - _document_buffer[xml_file.size() + 1] = '\0'; + _document_buffer.resize(_xml_content.size() + 2); + memcpy(_document_buffer.data(), _xml_content.data(), _xml_content.size()); + _document_buffer[_xml_content.size()] = '\0'; + _document_buffer[_xml_content.size() + 1] = '\0'; _xml_doc.parse<0>(_document_buffer.data()); return true; diff --git a/src/fw-logs/fw-logs-xml-helper.h b/src/fw-logs/fw-logs-xml-helper.h index c9f5a31226..39b6c963d5 100644 --- a/src/fw-logs/fw-logs-xml-helper.h +++ b/src/fw-logs/fw-logs-xml-helper.h @@ -22,7 +22,7 @@ namespace librealsense none }; - fw_logs_xml_helper(std::string xml_full_file_path); + fw_logs_xml_helper(std::string xml_content); ~fw_logs_xml_helper(void); bool build_log_meta_data(fw_logs_formating_options* logs_formating_options); @@ -40,7 +40,7 @@ namespace librealsense bool try_load_external_xml(); bool _init_done; - std::string _xml_full_file_path; + std::string _xml_content; xml_document<> _xml_doc; std::vector _document_buffer; }; diff --git a/src/rs.cpp b/src/rs.cpp index 320650286c..7cebf0e3fa 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -3056,15 +3056,15 @@ unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, r } HANDLE_EXCEPTIONS_AND_RETURN(0, msg) -int rs2_init_parser(rs2_device* dev, const char* xml_path ,rs2_error** error) BEGIN_API_CALL +int rs2_init_parser(rs2_device* dev, const char* xml_content,rs2_error** error) BEGIN_API_CALL { - VALIDATE_NOT_NULL(xml_path); + VALIDATE_NOT_NULL(xml_content); auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); - return (fw_loggerable->init_parser(xml_path)) ? 1 : 0; + return (fw_loggerable->init_parser(xml_content)) ? 1 : 0; } -HANDLE_EXCEPTIONS_AND_RETURN(0, xml_path) +HANDLE_EXCEPTIONS_AND_RETURN(0, xml_content) rs2_firmware_log_parsed_message* rs2_create_firmware_log_parsed_message(rs2_device* dev, rs2_error** error)BEGIN_API_CALL { diff --git a/tools/fw-logger/rs-fw-logger.cpp b/tools/fw-logger/rs-fw-logger.cpp index aadf665e52..8188b70d6b 100644 --- a/tools/fw-logger/rs-fw-logger.cpp +++ b/tools/fw-logger/rs-fw-logger.cpp @@ -76,7 +76,8 @@ int main(int argc, char* argv[]) ifstream f(xml_full_file_path); if (f.good()) { - bool parser_initialized = fw_log_device.init_parser(xml_full_file_path); + std::string xml_content((std::istreambuf_iterator(f)), std::istreambuf_iterator()); + bool parser_initialized = fw_log_device.init_parser(xml_content); if (parser_initialized) using_parser = true; } From 0a038223dbef0185e75991cb87ec437035236b71 Mon Sep 17 00:00:00 2001 From: remibettan Date: Tue, 16 Jun 2020 11:54:17 +0300 Subject: [PATCH 21/43] modify fw-logger tool so that it could pull also flash logs --- tools/fw-logger/rs-fw-logger.cpp | 44 ++++++++++++++++++++++++++------ 1 file changed, 36 insertions(+), 8 deletions(-) diff --git a/tools/fw-logger/rs-fw-logger.cpp b/tools/fw-logger/rs-fw-logger.cpp index 8188b70d6b..4838cdc524 100644 --- a/tools/fw-logger/rs-fw-logger.cpp +++ b/tools/fw-logger/rs-fw-logger.cpp @@ -47,7 +47,9 @@ int main(int argc, char* argv[]) { CmdLine cmd("librealsense rs-fw-logger example tool", ' ', RS2_API_VERSION_STR); ValueArg xml_arg("l", "load", "Full file path of HW Logger Events XML file", false, "", "Load HW Logger Events XML file"); - cmd.add(xml_arg); + SwitchArg flash_logs_arg("f", "flash", "Flash Logs Request", false); + cmd.add(xml_arg); + cmd.add(flash_logs_arg); cmd.parse(argc, argv); log_to_file(RS2_LOG_SEVERITY_WARN, "librealsense.log"); @@ -55,10 +57,14 @@ int main(int argc, char* argv[]) auto use_xml_file = false; auto xml_full_file_path = xml_arg.getValue(); + bool are_flash_logs_requested = flash_logs_arg.isSet(); + context ctx; device_hub hub(ctx); - while (true) + bool should_loop_end = false; + + while (!should_loop_end) { try { @@ -83,17 +89,32 @@ int main(int argc, char* argv[]) } } + bool are_there_remaining_flash_logs_to_pull = true; + while (hub.is_connected(dev)) { - auto fw_log_message = fw_log_device.create_message(); - bool result = fw_log_device.get_firmware_log(fw_log_message); + if (are_flash_logs_requested && !are_there_remaining_flash_logs_to_pull) + { + should_loop_end = true; + break; + } + auto log_message = fw_log_device.create_message(); + bool result = false; + if (are_flash_logs_requested) + { + result = fw_log_device.get_flash_log(log_message); + } + else + { + result = fw_log_device.get_firmware_log(log_message); + } if (result) { std::vector fw_log_lines; if (using_parser) { auto parsed_log = fw_log_device.create_parsed_message(); - bool parsing_result = fw_log_device.parse_log(fw_log_message, parsed_log); + bool parsing_result = fw_log_device.parse_log(log_message, parsed_log); stringstream sstr; sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() @@ -105,10 +126,10 @@ int main(int argc, char* argv[]) else { stringstream sstr; - sstr << fw_log_message.get_timestamp(); - sstr << " " << fw_log_message.get_severity_str(); + sstr << log_message.get_timestamp(); + sstr << " " << log_message.get_severity_str(); sstr << " FW_Log_Data:"; - std::vector msg_data = fw_log_message.data(); + std::vector msg_data = log_message.data(); for (int i = 0; i < msg_data.size(); ++i) { sstr << char2hex(raw_data[i]) << " "; @@ -118,6 +139,13 @@ int main(int argc, char* argv[]) for (auto& line : fw_log_lines) cout << line << endl; } + else + { + if (are_flash_logs_requested) + { + are_there_remaining_flash_logs_to_pull = false; + } + } } } catch (const error & e) From 6fc4ee727e6d17902acc229a3c91baebf5f82ae0 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 09:38:45 +0300 Subject: [PATCH 22/43] fw logs code corrections --- include/librealsense2/hpp/rs_firmware_logs.hpp | 1 - src/firmware_logger_device.cpp | 16 +++++++--------- 2 files changed, 7 insertions(+), 10 deletions(-) diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp index c80f68ee45..1cb76954f1 100644 --- a/include/librealsense2/hpp/rs_firmware_logs.hpp +++ b/include/librealsense2/hpp/rs_firmware_logs.hpp @@ -7,7 +7,6 @@ #include "rs_types.hpp" #include "rs_sensor.hpp" #include "../h/rs_firmware_logs.h" -#include namespace rs2 { diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 05f45d52aa..bb512e135f 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -48,7 +48,8 @@ namespace librealsense auto res = _hw_monitor->send(_input_code_for_fw_logs); if (res.empty()) { - throw std::runtime_error("Getting Firmware logs failed!"); + LOG_INFO("Getting Firmware logs failed!"); + return; } //erasing header @@ -71,24 +72,21 @@ namespace librealsense void firmware_logger_device::get_flash_logs_from_hw_monitor() { - int size_of_flash_logs_header = 31; + int size_of_flash_logs_header = 27; auto res = _hw_monitor->send(_input_code_for_flash_logs); if (res.empty()) { - throw std::runtime_error("Getting Flash logs failed!"); + LOG_INFO("Getting Flash logs failed!"); + return; } - int limit = static_cast(res[0] + (res[1] << 8) + (res[2] << 16) + (res[3] << 24)); - //erasing header res.erase(res.begin(), res.begin() + size_of_flash_logs_header); auto beginOfLogIterator = res.begin(); - // convert bytes to fw_logs_binary_data - for (int i = 0; i < limit; ++i) + // convert bytes to flash_logs_binary_data + for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE && *beginOfLogIterator == 160; ++i) { - if (*beginOfLogIterator == 0) - break; auto endOfLogIterator = beginOfLogIterator + fw_logs::BINARY_DATA_SIZE; std::vector resultsForOneLog; resultsForOneLog.insert(resultsForOneLog.begin(), beginOfLogIterator, endOfLogIterator); From 08be3e7cabbdb1cc233aef0247da41971fee14b3 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 10:48:54 +0300 Subject: [PATCH 23/43] pids map added to fw logger, sr300 missing --- src/ds5/ds5-factory.cpp | 36 +++++------ src/firmware_logger_device.cpp | 108 ++++++++++++++++++++++++++++----- src/firmware_logger_device.h | 11 ++-- src/l500/l500-factory.cpp | 13 ++-- 4 files changed, 128 insertions(+), 40 deletions(-) diff --git a/src/ds5/ds5-factory.cpp b/src/ds5/ds5-factory.cpp index 6d63e88708..64b3aa22da 100644 --- a/src/ds5/ds5-factory.cpp +++ b/src/ds5/ds5-factory.cpp @@ -39,7 +39,7 @@ namespace librealsense ds5_device(ctx, group), ds5_nonmonochrome(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -75,7 +75,7 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5u_device(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -127,7 +127,7 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -165,7 +165,7 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -203,7 +203,7 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -256,7 +256,7 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -306,7 +306,7 @@ namespace librealsense ds5_device(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -350,7 +350,7 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5_device(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -387,7 +387,7 @@ namespace librealsense ds5_device(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -425,7 +425,7 @@ namespace librealsense ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), ds5_motion(ctx, group), - firmware_logger_device(ds5_device::_hw_monitor) + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::vector get_profiles_tags() const override @@ -467,7 +467,7 @@ namespace librealsense ds5_active(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -515,7 +515,7 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -556,7 +556,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -597,7 +597,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) { check_and_restore_rgb_stream_extrinsic(); } @@ -815,7 +815,7 @@ namespace librealsense ds5_motion(ctx, group), ds5_nonmonochrome(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -851,7 +851,7 @@ namespace librealsense ds5_device(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) {} + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -881,7 +881,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -926,7 +926,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor) + firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index bb512e135f..2766a7f249 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -2,24 +2,96 @@ // Copyright(c) 2020 Intel Corporation. All Rights Reserved. #include "firmware_logger_device.h" +#include "ds5/ds5-private.h" +#include "l500/l500-private.h" +#include "ivcam/sr300.h" #include namespace librealsense { - firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor) : + std::map firmware_logger_device::fw_logs_commands = + { + {ds::RS400_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS410_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS415_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS430_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS430_MM_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS_USB2_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS_RECOVERY_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS_USB2_RECOVERY_PID, command{ ds::GLD, 0x1f4 }}, + {ds::RS400_IMU_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS420_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS420_MM_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS410_MM_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS400_MM_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS430_MM_RGB_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS460_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS435_RGB_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS405U_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS435I_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS416_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS430I_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS465_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS416_RGB_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS405_PID , command{ ds::GLD, 0x1f4 }}, + {ds::RS455_PID , command{ ds::GLD, 0x1f4 }}, + {L500_RECOVERY_PID , command{ ivcam2::GLD, 0x1f4 }}, + {L500_PID , command{ ivcam2::GLD, 0x1f4 }}, + {L515_PID_PRE_PRQ , command{ ivcam2::GLD, 0x1f4 }}, + {L515_PID , command{ ivcam2::GLD, 0x1f4 }}, + {SR300_PID , command{ ivcam2::GLD, 0x1f4 }}, + {SR300v2_PID , command{ ivcam2::GLD, 0x1f4 }}, + {SR300_RECOVERY , command{ ivcam2::GLD, 0x1f4 }} + }; + + std::map firmware_logger_device::flash_logs_commands = + { + {ds::RS400_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS410_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS415_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS430_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS430_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS_USB2_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS_RECOVERY_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS_USB2_RECOVERY_PID, command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS400_IMU_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS420_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS420_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS410_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS400_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS430_MM_RGB_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS460_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS435_RGB_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS405U_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS435I_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS416_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS430I_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS465_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS416_RGB_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS405_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {ds::RS455_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, + {L500_RECOVERY_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, + {L500_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, + {L515_PID_PRE_PRQ , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, + {L515_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}/*, + {SR300_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, + {SR300v2_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, + {SR300_RECOVERY , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}*/ + }; + + + firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, + const synthetic_sensor& depth_sensor) : _hw_monitor(hardware_monitor), _fw_logs(), _flash_logs(), _flash_logs_initialized(false), _parser(nullptr) { - _input_code_for_fw_logs = { 0x14, 0x00, 0xab, 0xcd, 0x0f, 0x00, 0x00, 0x00, - 0xf4, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; - - _input_code_for_flash_logs = { 0x14, 0x00, 0xab, 0xcd, 0x09, 0x00, 0x00, 0x00, - 0x00, 0xa0, 0x17, 0x00, 0xf8, 0x03, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + std::string pid_str (depth_sensor.get_info(RS2_CAMERA_INFO_PRODUCT_ID)); + std::stringstream ss; + ss << std::hex << pid_str; + ss >> _device_pid; } bool firmware_logger_device::get_fw_log(fw_logs::fw_logs_binary_data& binary_data) @@ -44,17 +116,19 @@ namespace librealsense void firmware_logger_device::get_fw_logs_from_hw_monitor() { - int size_of_fw_logs_header = 4; - auto res = _hw_monitor->send(_input_code_for_fw_logs); + auto it = fw_logs_commands.find(_device_pid); + if (it == fw_logs_commands.end()) + { + LOG_INFO("Firmware logs not set for this device!"); + return; + } + auto res = _hw_monitor->send(it->second); if (res.empty()) { LOG_INFO("Getting Firmware logs failed!"); return; } - //erasing header - res.erase(res.begin(), res.begin() + size_of_fw_logs_header); - auto beginOfLogIterator = res.begin(); // convert bytes to fw_logs_binary_data for (int i = 0; i < res.size() / fw_logs::BINARY_DATA_SIZE; ++i) @@ -73,7 +147,13 @@ namespace librealsense void firmware_logger_device::get_flash_logs_from_hw_monitor() { int size_of_flash_logs_header = 27; - auto res = _hw_monitor->send(_input_code_for_flash_logs); + auto it = flash_logs_commands.find(_device_pid); + if (it == flash_logs_commands.end()) + { + LOG_INFO("Flash logs not set for this device!"); + return; + } + auto res = _hw_monitor->send(it->second); if (res.empty()) { LOG_INFO("Getting Flash logs failed!"); diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index d8b8a4a75f..77f86939d2 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -26,7 +26,8 @@ namespace librealsense class firmware_logger_device : public virtual device, public firmware_logger_extensions { public: - firmware_logger_device(std::shared_ptr hardware_monitor); + firmware_logger_device(std::shared_ptr hardware_monitor, + const synthetic_sensor& depth_sensor); bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; @@ -35,6 +36,9 @@ namespace librealsense bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; private: + static std::map fw_logs_commands; + static std::map flash_logs_commands; + void get_fw_logs_from_hw_monitor(); void get_flash_logs_from_hw_monitor(); @@ -45,10 +49,9 @@ namespace librealsense bool _flash_logs_initialized; - std::vector _input_code_for_fw_logs; - std::vector _input_code_for_flash_logs; - fw_logs::fw_logs_parser* _parser; + uint16_t _device_pid; + }; } \ No newline at end of file diff --git a/src/l500/l500-factory.cpp b/src/l500/l500-factory.cpp index 4bd7d2be6b..51297c5626 100644 --- a/src/l500/l500-factory.cpp +++ b/src/l500/l500-factory.cpp @@ -11,6 +11,7 @@ #include "context.h" #include "image.h" #include "metadata-parser.h" +#include "../firmware_logger_device.h" #include "l500-factory.h" #include "l500-depth.h" @@ -27,7 +28,8 @@ namespace librealsense public l500_options, public l500_color, public l500_motion, - public l500_serializable + public l500_serializable, + public firmware_logger_device { public: rs515_device(std::shared_ptr ctx, @@ -39,7 +41,8 @@ namespace librealsense l500_options(ctx, group), l500_color(ctx, group), l500_motion(ctx, group), - l500_serializable(_hw_monitor, get_depth_sensor()) + l500_serializable(l500_device::_hw_monitor, get_depth_sensor()), + firmware_logger_device(l500_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -59,7 +62,8 @@ namespace librealsense }; // l500 - class rs500_device : public l500_depth + class rs500_device : public l500_depth, + public firmware_logger_device { public: rs500_device(std::shared_ptr ctx, @@ -67,7 +71,8 @@ namespace librealsense bool register_device_notifications) : device(ctx, group, register_device_notifications), l500_device(ctx, group), - l500_depth(ctx, group) + l500_depth(ctx, group), + firmware_logger_device(l500_device::_hw_monitor, get_depth_sensor()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; From 8f037b14d318c0529a8af99cc4a41606ed4807b6 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 11:21:58 +0300 Subject: [PATCH 24/43] removing flash logs example as it is already in rs-fw-logger tool --- examples/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 59e516c697..cf04932166 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -47,4 +47,3 @@ add_subdirectory(ar-basic) add_subdirectory(ar-advanced) add_subdirectory(pose-apriltag) add_subdirectory(tracking-and-depth) -add_subdirectory(flash-logs) From 45ef2ff5d29fa9f34e880966f6aefcdf2905d8e2 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 11:52:19 +0300 Subject: [PATCH 25/43] adding fw logs support for sr300 --- src/firmware_logger_device.cpp | 8 ++++---- src/ivcam/sr300.cpp | 1 + src/ivcam/sr300.h | 8 ++++++-- 3 files changed, 11 insertions(+), 6 deletions(-) diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 2766a7f249..08cbe87ae1 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -73,10 +73,10 @@ namespace librealsense {L500_RECOVERY_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, {L500_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, {L515_PID_PRE_PRQ , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, - {L515_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}/*, - {SR300_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, - {SR300v2_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, - {SR300_RECOVERY , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}*/ + {L515_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, + {SR300_PID , command{ ivcam::FlashRead, 0x000B6000, 0x3f8 }}, + {SR300v2_PID , command{ ivcam::FlashRead, 0x000B6000, 0x3f8 }}, + {SR300_RECOVERY , command{ ivcam::FlashRead, 0x000B6000, 0x3f8 }} }; diff --git a/src/ivcam/sr300.cpp b/src/ivcam/sr300.cpp index 8329308522..0f52f5a00b 100644 --- a/src/ivcam/sr300.cpp +++ b/src/ivcam/sr300.cpp @@ -422,6 +422,7 @@ namespace librealsense const platform::backend_device_group& group, bool register_device_notifications) : device(ctx, group, register_device_notifications), + firmware_logger_device(_hw_monitor, get_depth_sensor()), _depth_device_idx(add_sensor(create_depth_device(ctx, depth))), _depth_stream(new stream(RS2_STREAM_DEPTH)), _ir_stream(new stream(RS2_STREAM_INFRARED)), diff --git a/src/ivcam/sr300.h b/src/ivcam/sr300.h index 18acb2461d..1db362cd58 100644 --- a/src/ivcam/sr300.h +++ b/src/ivcam/sr300.h @@ -21,6 +21,7 @@ #include "stream.h" #include "fw-update/fw-update-device-interface.h" #include "proc/color-formats-converter.h" +#include "../firmware_logger_device.h" namespace librealsense { @@ -185,7 +186,10 @@ namespace librealsense platform::usb_device_info _hwm; }; - class sr300_camera : public device, public debug_interface, public updatable + class sr300_camera : public device, + public debug_interface, + public updatable, + public firmware_logger_device { public: std::vector get_profiles_tags() const override @@ -386,7 +390,7 @@ namespace librealsense force_hardware_reset(); } - synthetic_sensor& get_depth_sensor() { return dynamic_cast(get_sensor(_depth_device_idx)); } + synthetic_sensor& get_depth_sensor() { return dynamic_cast(device::get_sensor(_depth_device_idx)); } uvc_sensor& get_raw_depth_sensor() { From a8d11e811522df00f8fb41805d8c509c1e8b2e30 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 12:40:44 +0300 Subject: [PATCH 26/43] removing not needed examples --- examples/firmware-logs/CMakeLists.txt | 16 --- examples/firmware-logs/rs-firmware-logs.cpp | 126 ------------------ examples/flash-logs/CMakeLists.txt | 16 --- examples/flash-logs/rs-flash-logs.cpp | 137 -------------------- 4 files changed, 295 deletions(-) delete mode 100644 examples/firmware-logs/CMakeLists.txt delete mode 100644 examples/firmware-logs/rs-firmware-logs.cpp delete mode 100644 examples/flash-logs/CMakeLists.txt delete mode 100644 examples/flash-logs/rs-flash-logs.cpp diff --git a/examples/firmware-logs/CMakeLists.txt b/examples/firmware-logs/CMakeLists.txt deleted file mode 100644 index 929185ad15..0000000000 --- a/examples/firmware-logs/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -# License: Apache 2.0. See LICENSE file in root directory. -# Copyright(c) 2020 Intel Corporation. All Rights Reserved. -# minimum required cmake version: 3.1.0 -cmake_minimum_required(VERSION 3.1.0) - -project(RealsenseExamplesFirmwareLogs) - -if(BUILD_GRAPHICAL_EXAMPLES) - add_executable(rs-firmware-logs rs-firmware-logs.cpp ../example.hpp) - set_property(TARGET rs-firmware-logs PROPERTY CXX_STANDARD 11) - target_link_libraries(rs-firmware-logs ${DEPENDENCIES}) - include_directories(rs-firmware-logs ../ ../../third-party/tclap/include) - set_target_properties (rs-firmware-logs PROPERTIES FOLDER "Examples") - - install(TARGETS rs-firmware-logs RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}) -endif() diff --git a/examples/firmware-logs/rs-firmware-logs.cpp b/examples/firmware-logs/rs-firmware-logs.cpp deleted file mode 100644 index 50c2bb6cbe..0000000000 --- a/examples/firmware-logs/rs-firmware-logs.cpp +++ /dev/null @@ -1,126 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2017 Intel Corporation. All Rights Reserved. - -#include // Include RealSense Cross Platform API -#include "example.hpp" // Include short list of convenience functions for rendering -#include -#include -#include -#include - -using namespace std; - - -string hexify(unsigned char n) -{ - string res; - - do - { - res += "0123456789ABCDEF"[n % 16]; - n >>= 4; - } while (n); - - reverse(res.begin(), res.end()); - - if (res.size() == 1) - { - res.insert(0, "0"); - } - - return res; -} - -string datetime_string() -{ - auto t = time(nullptr); - char buffer[20] = {}; - const tm* time = localtime(&t); - if (nullptr != time) - strftime(buffer, sizeof(buffer), "%Y-%m-%d %H:%M:%S", time); - - return string(buffer); -} - -// Capture Example demonstrates how to -// capture depth and color video streams and render them to the screen -int main(int argc, char * argv[]) -{ - // Declare RealSense pipeline, encapsulating the actual device and sensors - rs2::pipeline pipe; - - // Start streaming with default recommended configuration - // The default video configuration contains Depth and Color streams - // If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default - auto res = pipe.start(); - - rs2::context ctx; - rs2::device_hub hub(ctx); - while (true) - { - try - { - cout << "\nWaiting for RealSense device to connect...\n"; - auto dev = hub.wait_for_device(); - cout << "RealSense device was connected...\n"; - - setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout - - auto fw_log_device = res.get_device().as(); - - bool using_parser = false; - std::string xml_path("C:\\Users\\rbettan\\Documents\\Dev\\RefFolder\\HWLoggerEventsDS5.xml"); - if (!xml_path.empty()) - { - ifstream f(xml_path); - if (f.good()) - { - bool parser_initialized = fw_log_device.init_parser(xml_path); - if (parser_initialized) - using_parser = true; - } - } - - while (hub.is_connected(dev)) - { - auto fw_log_message = fw_log_device.create_message(); - bool result = fw_log_device.get_firmware_log(fw_log_message); - if (result) - { - std::vector fw_log_lines; - if (using_parser) - { - rs2::firmware_log_parsed_message parsed_log = fw_log_device.parse_log(fw_log_message); - stringstream sstr; - sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() - << " " << parsed_log.thread_name() << " " << parsed_log.file_name() - << " " << parsed_log.line(); - - fw_log_lines.push_back(sstr.str()); - } - else - { - stringstream sstr; - sstr << fw_log_message.get_timestamp(); - sstr << " " << fw_log_message.get_severity_str(); - sstr << " FW_Log_Data:"; - std::vector msg_data = fw_log_message.data(); - for (int i = 0; i < msg_data.size(); ++i) - { - sstr << hexify(msg_data[i]) << " "; - } - fw_log_lines.push_back(sstr.str()); - } - for (auto& line : fw_log_lines) - cout << line << endl; - } - } - } - catch (const rs2::error & e) - { - cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << endl; - } - } - - return EXIT_SUCCESS; -} diff --git a/examples/flash-logs/CMakeLists.txt b/examples/flash-logs/CMakeLists.txt deleted file mode 100644 index fac7fe82c8..0000000000 --- a/examples/flash-logs/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -# License: Apache 2.0. See LICENSE file in root directory. -# Copyright(c) 2020 Intel Corporation. All Rights Reserved. -# minimum required cmake version: 3.1.0 -cmake_minimum_required(VERSION 3.1.0) - -project(RealsenseExamplesFirmwareLogs) - -if(BUILD_GRAPHICAL_EXAMPLES) - add_executable(rs-flash-logs rs-flash-logs.cpp ../example.hpp) - set_property(TARGET rs-flash-logs PROPERTY CXX_STANDARD 11) - target_link_libraries(rs-flash-logs ${DEPENDENCIES}) - include_directories(rs-flash-logs ../ ../../third-party/tclap/include) - set_target_properties (rs-flash-logs PROPERTIES FOLDER "Examples") - - install(TARGETS rs-flash-logs RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR}) -endif() diff --git a/examples/flash-logs/rs-flash-logs.cpp b/examples/flash-logs/rs-flash-logs.cpp deleted file mode 100644 index 25c5d45aa4..0000000000 --- a/examples/flash-logs/rs-flash-logs.cpp +++ /dev/null @@ -1,137 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2017 Intel Corporation. All Rights Reserved. - -#include // Include RealSense Cross Platform API -#include "example.hpp" // Include short list of convenience functions for rendering -#include -#include -#include -#include - -using namespace std; - - -string hexify(unsigned char n) -{ - string res; - - do - { - res += "0123456789ABCDEF"[n % 16]; - n >>= 4; - } while (n); - - reverse(res.begin(), res.end()); - - if (res.size() == 1) - { - res.insert(0, "0"); - } - - return res; -} - -string datetime_string() -{ - auto t = time(nullptr); - char buffer[20] = {}; - const tm* time = localtime(&t); - if (nullptr != time) - strftime(buffer, sizeof(buffer), "%Y-%m-%d %H:%M:%S", time); - - return string(buffer); -} - -// Capture Example demonstrates how to -// capture depth and color video streams and render them to the screen -int main(int argc, char * argv[]) -{ - // Declare RealSense pipeline, encapsulating the actual device and sensors - rs2::pipeline pipe; - - // Start streaming with default recommended configuration - // The default video configuration contains Depth and Color streams - // If a device is capable to stream IMU data, both Gyro and Accelerometer are enabled by default - auto res = pipe.start(); - - rs2::context ctx; - rs2::device_hub hub(ctx); - - try - { - cout << "\nWaiting for RealSense device to connect...\n"; - auto dev = hub.wait_for_device(); - cout << "RealSense device was connected...\n"; - - setvbuf(stdout, NULL, _IONBF, 0); // unbuffering stdout - - - auto fw_log_device = res.get_device().as(); - - bool using_parser = false; - std::string xml_full_file_path("HWLoggerEventsDS5.xml"); - if (!xml_full_file_path.empty()) - { - ifstream f(xml_full_file_path); - if (f.good()) - { - std::string xml_content((std::istreambuf_iterator(f)), std::istreambuf_iterator()); - bool parser_initialized = fw_log_device.init_parser(xml_content); - if (parser_initialized) - using_parser = true; - } - } - - bool flash_logs_to_pull = true; - while (hub.is_connected(dev) && flash_logs_to_pull) - { - auto flash_log_message = fw_log_device.create_message(); - bool result = fw_log_device.get_flash_log(flash_log_message); - if (result) - { - std::vector fw_log_lines; - - static bool usingParser = true; - if (usingParser) - { - - auto parsed_log = fw_log_device.create_parsed_message(); - bool parsing_result = fw_log_device.parse_log(flash_log_message, parsed_log); - - stringstream sstr; - sstr << parsed_log.timestamp() << " " << parsed_log.severity() << " " << parsed_log.message() - << " " << parsed_log.thread_name() << " " << parsed_log.file_name() - << " " << parsed_log.line(); - - fw_log_lines.push_back(sstr.str()); - - } - else - { - stringstream sstr; - sstr << flash_log_message.get_timestamp(); - sstr << " " << flash_log_message.get_severity_str(); - sstr << " FW_Log_Data:"; - std::vector msg_data = flash_log_message.data(); - for (int i = 0; i < msg_data.size(); ++i) - { - sstr << hexify(msg_data[i]) << " "; - } - fw_log_lines.push_back(sstr.str()); - } - for (auto& line : fw_log_lines) - cout << line << endl; - } - else - { - flash_logs_to_pull = false; - } - } - } - catch (const rs2::error & e) - { - cerr << "RealSense error calling " << e.get_failed_function() << "(" << e.get_failed_args() << "):\n " << e.what() << endl; - } - - return EXIT_SUCCESS; -} From 939d364468b076101efd9ac6d5a25552bd8dd3d8 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 12:46:24 +0300 Subject: [PATCH 27/43] removing not needed unit tests --- unit-tests/fw-logs/fw-logs-common.h | 37 ------ .../fw-logs/test-c-get-fw-logs-not-parsed.cpp | 80 ------------ .../fw-logs/test-c-get-fw-logs-parsed.cpp | 114 ------------------ 3 files changed, 231 deletions(-) delete mode 100644 unit-tests/fw-logs/fw-logs-common.h delete mode 100644 unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp delete mode 100644 unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp diff --git a/unit-tests/fw-logs/fw-logs-common.h b/unit-tests/fw-logs/fw-logs-common.h deleted file mode 100644 index af25dced2a..0000000000 --- a/unit-tests/fw-logs/fw-logs-common.h +++ /dev/null @@ -1,37 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2020 Intel Corporation. All Rights Reserved. - -#pragma once - -//#include // Include RealSense Cross Platform API - -#include -#ifdef BUILD_SHARED_LIBS -// With static linkage, ELPP is initialized by librealsense, so doing it here will -// create errors. When we're using the shared .so/.dll, the two are separate and we have -// to initialize ours if we want to use the APIs! -INITIALIZE_EASYLOGGINGPP -#endif - -// Catch also defines CHECK(), and so we have to undefine it or we get compilation errors! -#undef CHECK - -// Let Catch define its own main() function -#define CATCH_CONFIG_MAIN -#include "../catch/catch.hpp" - -// Define our own logging macro for debugging to stdout -// Can possibly turn it on automatically based on the Catch options supplied -// on the command-line, with a custom main(): -// Catch::Session catch_session; -// int main (int argc, char * const argv[]) { -// return catch_session.run( argc, argv ); -// } -// #define TRACE(X) if( catch_session.configData().verbosity == ... ) {} -// With Catch2, we can turn this into SCOPED_INFO. -#define TRACE(X) do { \ - std::cout << X << std::endl; \ - } while(0) - - - diff --git a/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp b/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp deleted file mode 100644 index 73cfbc890d..0000000000 --- a/unit-tests/fw-logs/test-c-get-fw-logs-not-parsed.cpp +++ /dev/null @@ -1,80 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2020 Intel Corporation. All Rights Reserved. - -//#cmake:add-file fw-logs-common.h -#include "fw-logs-common.h" - -/* Include the librealsense C header files */ -#include - -//get fw logs using c api -TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { - - rs2_error* e = 0; - - // Create a context object. This object owns the handles to all connected realsense devices. - // The returned object should be released with rs2_delete_context(...) - rs2_context* ctx = rs2_create_context(RS2_API_VERSION, &e); - REQUIRE(e == 0); - - /* Get a list of all the connected devices. */ - // The returned object should be released with rs2_delete_device_list(...) - rs2_device_list* device_list = rs2_query_devices(ctx, &e); - REQUIRE(e == 0); - - int dev_count = rs2_get_device_count(device_list, &e); - REQUIRE(e == 0); - printf("There are %d connected RealSense devices.\n", dev_count); - REQUIRE(dev_count > 0); - - // Get the first connected device - // The returned object should be released with rs2_delete_device(...) - rs2_device* dev = rs2_create_device(device_list, 0, &e); - REQUIRE(e == 0); - - bool device_extendable_to_fw_logger = false; - if (rs2_is_device_extendable_to(dev, RS2_EXTENSION_FW_LOGGER, &e) != 0 && !e) - { - device_extendable_to_fw_logger = true; - } - REQUIRE(device_extendable_to_fw_logger); - - bool were_fw_logs_received_once = false; - while (1)//!were_fw_logs_received_once) - { - rs2_error* e = nullptr; - rs2_firmware_log_message* fw_log_msg = rs2_get_firmware_log(dev, &e); - - REQUIRE(fw_log_msg); - - int size = rs2_firmware_log_message_size(fw_log_msg, &e); - - auto start = rs2_firmware_log_message_data(fw_log_msg, &e); - - if (size > 0) - { - were_fw_logs_received_once = true; - //get time - time_t rawtime; - struct tm* timeinfo; - - time_t mytime = time(NULL); - char* time_str = ctime(&mytime); - time_str[strlen(time_str) - 1] = '\0'; - printf("message received %s - ", time_str); - - rs2_error* e = nullptr; - rs2_log_severity severity = rs2_get_fw_log_severity(fw_log_msg, &e); - printf("%s ", rs2_log_severity_to_string(severity)); - - for (int i = 0; i < size; ++i) - { - printf("%d ", *(start + i)); - } - printf("\n"); - } - - rs2_delete_firmware_log_message(fw_log_msg); - } - -} diff --git a/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp b/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp deleted file mode 100644 index 57e7a2c341..0000000000 --- a/unit-tests/fw-logs/test-c-get-fw-logs-parsed.cpp +++ /dev/null @@ -1,114 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2020 Intel Corporation. All Rights Reserved. - -//#cmake:add-file fw-logs-common.h -#include "fw-logs-common.h" - -/* Include the librealsense C header files */ -#include -#include -#include -#include -#include - - -#include -#define GetCurrentDir _getcwd - -char* rs2_firmware_log_message_to_string(rs2_firmware_log_message msg) -{ - char* buffer = (char*)(malloc(50 * sizeof(char))); - sprintf(buffer, "message = %s", msg._message); - return buffer; -} - - -std::string get_current_dir() { - char buff[FILENAME_MAX]; //create string buffer to hold path - GetCurrentDir(buff, FILENAME_MAX); - std::string current_working_dir(buff); - return current_working_dir; -} - -//get fw logs using c api -TEST_CASE( "Getting FW logs in C", "[fw-logs]" ) { - - rs2_error* e = 0; - - // Create a context object. This object owns the handles to all connected realsense devices. - // The returned object should be released with rs2_delete_context(...) - rs2_context* ctx = rs2_create_context(RS2_API_VERSION, &e); - REQUIRE(e == 0); - - /* Get a list of all the connected devices. */ - // The returned object should be released with rs2_delete_device_list(...) - rs2_device_list* device_list = rs2_query_devices(ctx, &e); - REQUIRE(e == 0); - - int dev_count = rs2_get_device_count(device_list, &e); - REQUIRE(e == 0); - printf("There are %d connected RealSense devices.\n", dev_count); - REQUIRE(dev_count > 0); - - // Get the first connected device - // The returned object should be released with rs2_delete_device(...) - rs2_device* dev = rs2_create_device(device_list, 0, &e); - REQUIRE(e == 0); - - bool device_extendable_to_fw_logger = false; - if (rs2_is_device_extendable_to(dev, RS2_EXTENSION_FW_LOGGER, &e) != 0 && !e) - { - device_extendable_to_fw_logger = true; - } - REQUIRE(device_extendable_to_fw_logger); - - const char* xml_path_const = "HWLoggerEventsDS5.xml"; - - /*std::string cf = get_current_dir(); - std::string xml_path(xml_path_const); - - if (!xml_path.empty()) - { - std::ifstream f(xml_path); - if (f.good()) - { - int a = 1; - } - else { - - int b = 1; - } - }*/ - - rs2_firmware_logs_parser* parser = rs2_create_firmware_logs_parser(xml_path_const, &e); - REQUIRE(parser); - - bool were_fw_logs_received_once = false; - while (!were_fw_logs_received_once) - { - rs2_firmware_log_message_list* fw_logs_list = rs2_get_firmware_logs_list(dev, &e); - REQUIRE(fw_logs_list); - - if (fw_logs_list->_number_of_messages > 0) - { - were_fw_logs_received_once = true; - for (int i = 0; i < fw_logs_list->_number_of_messages; ++i) - { - rs2_firmware_log_message* msg = &fw_logs_list->_messages[i]; - /*rs2_raw_data_buffer* parsed_log = rs2_parse_firmware_log(parser, msg->_event_id, msg->_p1, msg->_p2, msg->_p3, - msg->_file_id, msg->_thread_id, &e);*/ - - rs2_parse_firmware_log(parser, &msg, &e); - rs2::error::handle(e); - - printf("message received: %s\n", rs2_firmware_log_message_to_string(*msg)); - - - } - } - rs2_delete_firmware_logs_list(fw_logs_list); - } - - rs2_delete_firmware_logs_parser(parser); - -} From cc9bfa7ef47b6b09cf277a935c264d96a4c325e9 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 13:34:25 +0300 Subject: [PATCH 28/43] api functions names got shorter - fw instead of firmware --- include/librealsense2/h/rs_firmware_logs.h | 20 +++++++++---------- .../librealsense2/hpp/rs_firmware_logs.hpp | 20 +++++++++---------- src/realsense.def | 20 +++++++++---------- src/rs.cpp | 20 +++++++++---------- 4 files changed, 40 insertions(+), 40 deletions(-) diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h index 6d1aa71dee..86dae1f146 100644 --- a/include/librealsense2/h/rs_firmware_logs.h +++ b/include/librealsense2/h/rs_firmware_logs.h @@ -21,7 +21,7 @@ extern "C" { * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return pointer to created empty firmware log message */ -rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_error** error); +rs2_firmware_log_message* rs2_create_fw_log_message(rs2_device* dev, rs2_error** error); /** * \brief Gets RealSense firmware log. @@ -30,7 +30,7 @@ rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_e * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor */ -int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); +int rs2_get_fw_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); /** * \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device @@ -45,7 +45,7 @@ int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs * Delete RealSense firmware log message * \param[in] device Realsense firmware log message to delete */ -void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg); +void rs2_delete_fw_log_message(rs2_firmware_log_message* msg); /** * \brief Gets RealSense firmware log message data. @@ -53,7 +53,7 @@ void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg); * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return pointer to start of the firmware log message data */ -const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); +const unsigned char* rs2_fw_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); /** * \brief Gets RealSense firmware log message size. @@ -61,7 +61,7 @@ const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return size of the firmware log message data */ -int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); +int rs2_fw_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); /** @@ -78,7 +78,7 @@ unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, r * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return severity of the firmware log message data */ -rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); +rs2_log_severity rs2_fw_log_message_timestamp(const rs2_firmware_log_message* msg, rs2_error** error); /** * \brief Initializes RealSense firmware logs parser in device. @@ -87,7 +87,7 @@ rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_messag * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails */ -int rs2_init_parser(rs2_device* dev, const char* xml_content, rs2_error** error); +int rs2_init_fw_log_parser(rs2_device* dev, const char* xml_content, rs2_error** error); /** @@ -96,13 +96,13 @@ int rs2_init_parser(rs2_device* dev, const char* xml_content, rs2_error** error) * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return pointer to created empty firmware log message */ -rs2_firmware_log_parsed_message* rs2_create_firmware_log_parsed_message(rs2_device* dev, rs2_error** error); +rs2_firmware_log_parsed_message* rs2_create_fw_log_parsed_message(rs2_device* dev, rs2_error** error); /** * \brief Deletes RealSense firmware log parsed message. * \param[in] msg message to be deleted */ -void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); +void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); /** @@ -119,7 +119,7 @@ int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg * Delete RealSense firmware log parsed message * \param[in] device Realsense firmware log parsed message to delete */ -void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); +void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); /** * \brief Gets RealSense firmware log parsed message message. diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp index 1cb76954f1..f0247d12b0 100644 --- a/include/librealsense2/hpp/rs_firmware_logs.hpp +++ b/include/librealsense2/hpp/rs_firmware_logs.hpp @@ -18,7 +18,7 @@ namespace rs2 rs2_log_severity get_severity() const { rs2_error* e = nullptr; - rs2_log_severity severity = rs2_firmware_log_message_severity(_fw_log_message.get(), &e); + rs2_log_severity severity = rs2_fw_log_message_timestamp(_fw_log_message.get(), &e); error::handle(e); return severity; } @@ -37,7 +37,7 @@ namespace rs2 int size() const { rs2_error* e = nullptr; - int size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); + int size = rs2_fw_log_message_size(_fw_log_message.get(), &e); error::handle(e); return size; } @@ -45,12 +45,12 @@ namespace rs2 std::vector data() const { rs2_error* e = nullptr; - auto size = rs2_firmware_log_message_size(_fw_log_message.get(), &e); + auto size = rs2_fw_log_message_size(_fw_log_message.get(), &e); error::handle(e); std::vector result; if (size > 0) { - auto start = rs2_firmware_log_message_data(_fw_log_message.get(), &e); + auto start = rs2_fw_log_message_data(_fw_log_message.get(), &e); error::handle(e); result.insert(result.begin(), start, start + size); } @@ -136,8 +136,8 @@ namespace rs2 { rs2_error* e = nullptr; std::shared_ptr msg( - rs2_create_firmware_log_message(_dev.get(), &e), - rs2_delete_firmware_log_message); + rs2_create_fw_log_message(_dev.get(), &e), + rs2_delete_fw_log_message); error::handle(e); return firmware_log_message(msg); @@ -147,8 +147,8 @@ namespace rs2 { rs2_error* e = nullptr; std::shared_ptr msg( - rs2_create_firmware_log_parsed_message(_dev.get(), &e), - rs2_delete_firmware_log_parsed_message); + rs2_create_fw_log_parsed_message(_dev.get(), &e), + rs2_delete_fw_log_parsed_message); error::handle(e); return firmware_log_parsed_message(msg); @@ -159,7 +159,7 @@ namespace rs2 rs2_error* e = nullptr; rs2_firmware_log_message* m = msg.get_message().get(); bool fw_log_pulling_status = - rs2_get_firmware_log(_dev.get(), &(m), &e); + rs2_get_fw_log(_dev.get(), &(m), &e); error::handle(e); @@ -182,7 +182,7 @@ namespace rs2 { rs2_error* e = nullptr; - bool parser_initialized = rs2_init_parser(_dev.get(), xml_content.c_str(), &e); + bool parser_initialized = rs2_init_fw_log_parser(_dev.get(), xml_content.c_str(), &e); error::handle(e); return parser_initialized; diff --git a/src/realsense.def b/src/realsense.def index d013030882..ca1fc5ad61 100644 --- a/src/realsense.def +++ b/src/realsense.def @@ -356,18 +356,18 @@ EXPORTS rs2_get_calibration_table rs2_set_calibration_table - rs2_create_firmware_log_message - rs2_delete_firmware_log_message - rs2_get_firmware_log + rs2_create_fw_log_message + rs2_delete_fw_log_message + rs2_get_fw_log rs2_get_flash_log - rs2_firmware_log_message_severity - rs2_firmware_log_message_timestamp - rs2_firmware_log_message_data - rs2_firmware_log_message_size - rs2_init_parser + rs2_fw_log_message_severity + rs2_fw_log_message_timestamp + rs2_fw_log_message_data + rs2_fw_log_message_size + rs2_init_fw_log_parser rs2_parse_firmware_log - rs2_create_firmware_log_parsed_message - rs2_delete_firmware_log_parsed_message + rs2_create_fw_log_parsed_message + rs2_delete_fw_log_parsed_message rs2_get_fw_log_parsed_message rs2_get_fw_log_parsed_file_name rs2_get_fw_log_parsed_thread_name diff --git a/src/rs.cpp b/src/rs.cpp index 7cebf0e3fa..3869d5dc1c 100644 --- a/src/rs.cpp +++ b/src/rs.cpp @@ -2982,7 +2982,7 @@ void rs2_load_json(rs2_device* dev, const void* json_content, unsigned content_s } HANDLE_EXCEPTIONS_AND_RETURN(, dev, json_content, content_size) -rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_error** error)BEGIN_API_CALL +rs2_firmware_log_message* rs2_create_fw_log_message(rs2_device* dev, rs2_error** error)BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); auto fw_loggerable = VALIDATE_INTERFACE(dev->device, librealsense::firmware_logger_extensions); @@ -2991,7 +2991,7 @@ rs2_firmware_log_message* rs2_create_firmware_log_message(rs2_device* dev, rs2_e } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, dev) -int rs2_get_firmware_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error) BEGIN_API_CALL +int rs2_get_fw_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); VALIDATE_NOT_NULL(fw_log_msg); @@ -3022,41 +3022,41 @@ int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs return result ? 1 : 0; } HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg) -void rs2_delete_firmware_log_message(rs2_firmware_log_message* msg) BEGIN_API_CALL +void rs2_delete_fw_log_message(rs2_firmware_log_message* msg) BEGIN_API_CALL { VALIDATE_NOT_NULL(msg); delete msg; } NOEXCEPT_RETURN(, msg) -const unsigned char* rs2_firmware_log_message_data(rs2_firmware_log_message* msg, rs2_error** error)BEGIN_API_CALL +const unsigned char* rs2_fw_log_message_data(rs2_firmware_log_message* msg, rs2_error** error)BEGIN_API_CALL { VALIDATE_NOT_NULL(msg); return msg->firmware_log_binary_data->logs_buffer.data(); } HANDLE_EXCEPTIONS_AND_RETURN(nullptr, msg) -int rs2_firmware_log_message_size(rs2_firmware_log_message* msg, rs2_error** error)BEGIN_API_CALL +int rs2_fw_log_message_size(rs2_firmware_log_message* msg, rs2_error** error)BEGIN_API_CALL { VALIDATE_NOT_NULL(msg); return msg->firmware_log_binary_data->logs_buffer.size(); } HANDLE_EXCEPTIONS_AND_RETURN(0, msg) -rs2_log_severity rs2_firmware_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL +rs2_log_severity rs2_fw_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL { return msg->firmware_log_binary_data->get_severity(); } HANDLE_EXCEPTIONS_AND_RETURN(RS2_LOG_SEVERITY_NONE, msg) -unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL +unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(msg); return msg->firmware_log_binary_data->get_timestamp(); } HANDLE_EXCEPTIONS_AND_RETURN(0, msg) -int rs2_init_parser(rs2_device* dev, const char* xml_content,rs2_error** error) BEGIN_API_CALL +int rs2_init_fw_log_parser(rs2_device* dev, const char* xml_content,rs2_error** error) BEGIN_API_CALL { VALIDATE_NOT_NULL(xml_content); @@ -3066,7 +3066,7 @@ int rs2_init_parser(rs2_device* dev, const char* xml_content,rs2_error** error) } HANDLE_EXCEPTIONS_AND_RETURN(0, xml_content) -rs2_firmware_log_parsed_message* rs2_create_firmware_log_parsed_message(rs2_device* dev, rs2_error** error)BEGIN_API_CALL +rs2_firmware_log_parsed_message* rs2_create_fw_log_parsed_message(rs2_device* dev, rs2_error** error)BEGIN_API_CALL { VALIDATE_NOT_NULL(dev); @@ -3091,7 +3091,7 @@ int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg } HANDLE_EXCEPTIONS_AND_RETURN(0, dev, fw_log_msg) -void rs2_delete_firmware_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg) BEGIN_API_CALL +void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg) BEGIN_API_CALL { VALIDATE_NOT_NULL(fw_log_parsed_msg); delete fw_log_parsed_msg; From 8b858ba323962ea2a7fb171bdffd85864013b9e2 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 19:16:18 +0300 Subject: [PATCH 29/43] fw-logger tool readme updated, fw_logger_device improved --- include/librealsense2/h/rs_firmware_logs.h | 4 +- .../librealsense2/hpp/rs_firmware_logs.hpp | 4 +- src/firmware_logger_device.cpp | 146 +++++++++--------- src/firmware_logger_device.h | 19 ++- src/ivcam/sr300.cpp | 1 - src/ivcam/sr300.h | 6 +- tools/fw-logger/readme.md | 8 +- 7 files changed, 102 insertions(+), 86 deletions(-) diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h index 86dae1f146..4e0f9c821b 100644 --- a/include/librealsense2/h/rs_firmware_logs.h +++ b/include/librealsense2/h/rs_firmware_logs.h @@ -70,7 +70,7 @@ int rs2_fw_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return timestamp of the firmware log message */ -unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error); +unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error); /** * \brief Gets RealSense firmware log message severity. @@ -78,7 +78,7 @@ unsigned int rs2_firmware_log_message_timestamp(rs2_firmware_log_message* msg, r * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return severity of the firmware log message data */ -rs2_log_severity rs2_fw_log_message_timestamp(const rs2_firmware_log_message* msg, rs2_error** error); +rs2_log_severity rs2_fw_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); /** * \brief Initializes RealSense firmware logs parser in device. diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp index f0247d12b0..1b1d005ba1 100644 --- a/include/librealsense2/hpp/rs_firmware_logs.hpp +++ b/include/librealsense2/hpp/rs_firmware_logs.hpp @@ -18,7 +18,7 @@ namespace rs2 rs2_log_severity get_severity() const { rs2_error* e = nullptr; - rs2_log_severity severity = rs2_fw_log_message_timestamp(_fw_log_message.get(), &e); + rs2_log_severity severity = rs2_fw_log_message_severity(_fw_log_message.get(), &e); error::handle(e); return severity; } @@ -29,7 +29,7 @@ namespace rs2 uint32_t get_timestamp() const { rs2_error* e = nullptr; - uint32_t timestamp = rs2_firmware_log_message_timestamp(_fw_log_message.get(), &e); + uint32_t timestamp = rs2_fw_log_message_timestamp(_fw_log_message.get(), &e); error::handle(e); return timestamp; } diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 08cbe87ae1..61d5697163 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -9,76 +9,62 @@ namespace librealsense { - std::map firmware_logger_device::fw_logs_commands = + std::map + firmware_logger_device::_logs_commands_per_group = { - {ds::RS400_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS410_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS415_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS430_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS430_MM_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS_USB2_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS_RECOVERY_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS_USB2_RECOVERY_PID, command{ ds::GLD, 0x1f4 }}, - {ds::RS400_IMU_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS420_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS420_MM_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS410_MM_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS400_MM_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS430_MM_RGB_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS460_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS435_RGB_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS405U_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS435I_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS416_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS430I_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS465_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS416_RGB_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS405_PID , command{ ds::GLD, 0x1f4 }}, - {ds::RS455_PID , command{ ds::GLD, 0x1f4 }}, - {L500_RECOVERY_PID , command{ ivcam2::GLD, 0x1f4 }}, - {L500_PID , command{ ivcam2::GLD, 0x1f4 }}, - {L515_PID_PRE_PRQ , command{ ivcam2::GLD, 0x1f4 }}, - {L515_PID , command{ ivcam2::GLD, 0x1f4 }}, - {SR300_PID , command{ ivcam2::GLD, 0x1f4 }}, - {SR300v2_PID , command{ ivcam2::GLD, 0x1f4 }}, - {SR300_RECOVERY , command{ ivcam2::GLD, 0x1f4 }} + {LOGS_COMMANDS_GROUP_DS, {command{ds::GLD, 0x1f4}, command{ds::FRB, 0x17a000, 0x3f8}}}, + {LOGS_COMMANDS_GROUP_L5, {command{ivcam2::GLD, 0x1f4}, command{ivcam2::FRB, 0x0011E000, 0x3f8}}}, + {LOGS_COMMANDS_GROUP_SR, {command{ivcam::GLD, 0x1f4}, command{ivcam::FlashRead, 0x000B6000, 0x3f8}}} }; - std::map firmware_logger_device::flash_logs_commands = - { - {ds::RS400_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS410_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS415_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS430_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS430_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS_USB2_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS_RECOVERY_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS_USB2_RECOVERY_PID, command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS400_IMU_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS420_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS420_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS410_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS400_MM_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS430_MM_RGB_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS460_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS435_RGB_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS405U_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS435I_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS416_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS430I_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS465_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS416_RGB_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS405_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {ds::RS455_PID , command{ ds::FRB, 0x17a000, 0x3f8 }}, - {L500_RECOVERY_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, - {L500_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, - {L515_PID_PRE_PRQ , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, - {L515_PID , command{ ivcam2::FRB, 0x0011E000, 0x3f8 }}, - {SR300_PID , command{ ivcam::FlashRead, 0x000B6000, 0x3f8 }}, - {SR300v2_PID , command{ ivcam::FlashRead, 0x000B6000, 0x3f8 }}, - {SR300_RECOVERY , command{ ivcam::FlashRead, 0x000B6000, 0x3f8 }} - }; + firmware_logger_device::logs_commands_group firmware_logger_device::get_logs_commands_group(uint16_t device_pid) + { + logs_commands_group group = LOGS_COMMANDS_GROUP_NONE; + switch (device_pid) + { + case ds::RS400_PID: + case ds::RS410_PID: + case ds::RS415_PID: + case ds::RS430_PID: + case ds::RS430_MM_PID: + case ds::RS_USB2_PID: + case ds::RS_RECOVERY_PID: + case ds::RS_USB2_RECOVERY_PID: + case ds::RS400_IMU_PID: + case ds::RS420_PID: + case ds::RS420_MM_PID: + case ds::RS410_MM_PID: + case ds::RS400_MM_PID: + case ds::RS430_MM_RGB_PID: + case ds::RS460_PID: + case ds::RS435_RGB_PID: + case ds::RS405U_PID: + case ds::RS435I_PID: + case ds::RS416_PID: + case ds::RS430I_PID: + case ds::RS465_PID: + case ds::RS416_RGB_PID: + case ds::RS405_PID: + case ds::RS455_PID: + group = LOGS_COMMANDS_GROUP_DS; + break; + case L500_RECOVERY_PID: + case L500_PID: + case L515_PID_PRE_PRQ: + case L515_PID: + group = LOGS_COMMANDS_GROUP_L5; + break; + case SR300_PID: + case SR300v2_PID: + case SR300_RECOVERY: + group = LOGS_COMMANDS_GROUP_SR; + break; + default: + break; + } + return group; + } firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, const synthetic_sensor& depth_sensor) : @@ -116,13 +102,19 @@ namespace librealsense void firmware_logger_device::get_fw_logs_from_hw_monitor() { - auto it = fw_logs_commands.find(_device_pid); - if (it == fw_logs_commands.end()) + logs_commands_group group = get_logs_commands_group(_device_pid); + if (group == LOGS_COMMANDS_GROUP_NONE) + { + LOG_INFO("Firmware logs not set for this device!"); + return; + } + auto it = _logs_commands_per_group.find(group); + if (it == _logs_commands_per_group.end()) { LOG_INFO("Firmware logs not set for this device!"); return; } - auto res = _hw_monitor->send(it->second); + auto res = _hw_monitor->send(it->second.fw_logs_command); if (res.empty()) { LOG_INFO("Getting Firmware logs failed!"); @@ -146,14 +138,20 @@ namespace librealsense void firmware_logger_device::get_flash_logs_from_hw_monitor() { - int size_of_flash_logs_header = 27; - auto it = flash_logs_commands.find(_device_pid); - if (it == flash_logs_commands.end()) + logs_commands_group group = get_logs_commands_group(_device_pid); + if (group == LOGS_COMMANDS_GROUP_NONE) { LOG_INFO("Flash logs not set for this device!"); return; } - auto res = _hw_monitor->send(it->second); + auto it = _logs_commands_per_group.find(group); + if (it == _logs_commands_per_group.end()) + { + LOG_INFO("Flash logs not set for this device!"); + return; + } + auto res = _hw_monitor->send(it->second.flash_logs_command); + if (res.empty()) { LOG_INFO("Getting Flash logs failed!"); @@ -161,6 +159,7 @@ namespace librealsense } //erasing header + int size_of_flash_logs_header = 27; res.erase(res.begin(), res.begin() + size_of_flash_logs_header); auto beginOfLogIterator = res.begin(); @@ -216,4 +215,5 @@ namespace librealsense return result; } + } \ No newline at end of file diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 77f86939d2..f715ada6db 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -22,7 +22,6 @@ namespace librealsense }; MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); - class firmware_logger_device : public virtual device, public firmware_logger_extensions { public: @@ -36,8 +35,22 @@ namespace librealsense bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; private: - static std::map fw_logs_commands; - static std::map flash_logs_commands; + enum logs_commands_group + { + LOGS_COMMANDS_GROUP_NONE, + LOGS_COMMANDS_GROUP_DS, + LOGS_COMMANDS_GROUP_L5, + LOGS_COMMANDS_GROUP_SR, + LOGS_COMMANDS_GROUP_COUNT + }; + struct logs_commands + { + command fw_logs_command; + command flash_logs_command; + }; + static std::map _logs_commands_per_group; + + logs_commands_group get_logs_commands_group(uint16_t device_pid); void get_fw_logs_from_hw_monitor(); void get_flash_logs_from_hw_monitor(); diff --git a/src/ivcam/sr300.cpp b/src/ivcam/sr300.cpp index 0f52f5a00b..8329308522 100644 --- a/src/ivcam/sr300.cpp +++ b/src/ivcam/sr300.cpp @@ -422,7 +422,6 @@ namespace librealsense const platform::backend_device_group& group, bool register_device_notifications) : device(ctx, group, register_device_notifications), - firmware_logger_device(_hw_monitor, get_depth_sensor()), _depth_device_idx(add_sensor(create_depth_device(ctx, depth))), _depth_stream(new stream(RS2_STREAM_DEPTH)), _ir_stream(new stream(RS2_STREAM_INFRARED)), diff --git a/src/ivcam/sr300.h b/src/ivcam/sr300.h index 1db362cd58..094c47c954 100644 --- a/src/ivcam/sr300.h +++ b/src/ivcam/sr300.h @@ -21,7 +21,6 @@ #include "stream.h" #include "fw-update/fw-update-device-interface.h" #include "proc/color-formats-converter.h" -#include "../firmware_logger_device.h" namespace librealsense { @@ -186,10 +185,9 @@ namespace librealsense platform::usb_device_info _hwm; }; - class sr300_camera : public device, + class sr300_camera : public device, public debug_interface, - public updatable, - public firmware_logger_device + public updatable { public: std::vector get_profiles_tags() const override diff --git a/tools/fw-logger/readme.md b/tools/fw-logger/readme.md index 127b844837..1e3eb55e5c 100644 --- a/tools/fw-logger/readme.md +++ b/tools/fw-logger/readme.md @@ -5,7 +5,13 @@ If you are suspecting that you have an issue that is related to the camera’s firmware, please use this tool and provide the output together with the FW version number when you are creating an issue. In order to run this, ensure that your camera is streaming. This can be done using the [realsense-viewer](https://github.com/IntelRealSense/librealsense/tree/development/tools/realsense-viewer) or [rs-capture Sample](https://github.com/IntelRealSense/librealsense/tree/development/examples/capture) +## Command Line Parameters +|Flag |Description |Default| +|---|---|---| +|`-l `|xml file ful path, used to parse the logs|| +|`-f`|collect flash logs instead of firmware logs|| + ## Usage After installing `librealsense` run `rs-fw-logger` to launch the tool. -rs-fw-logger > filename – will save the FW logs to the filename. + From 7c835f716d852d79c0684b1ad5fbc2a2346a1574 Mon Sep 17 00:00:00 2001 From: remibettan Date: Wed, 17 Jun 2020 19:19:24 +0300 Subject: [PATCH 30/43] new line added at end of files --- src/firmware_logger_device.cpp | 2 +- src/firmware_logger_device.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 61d5697163..aa156ef531 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -216,4 +216,4 @@ namespace librealsense return result; } -} \ No newline at end of file +} diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index f715ada6db..dbe718d532 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -67,4 +67,4 @@ namespace librealsense }; -} \ No newline at end of file +} From fe906ba7d23637e89478d5152971ab226db1ba47 Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 11:45:49 +0300 Subject: [PATCH 31/43] tabs and typo corrections --- include/librealsense2/h/rs_firmware_logs.h | 2 +- src/fw-logs/CMakeLists.txt | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h index 4e0f9c821b..9ad98a17fd 100644 --- a/include/librealsense2/h/rs_firmware_logs.h +++ b/include/librealsense2/h/rs_firmware_logs.h @@ -122,7 +122,7 @@ int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); /** -* \brief Gets RealSense firmware log parsed message message. +* \brief Gets RealSense firmware log parsed message. * \param[in] fw_log_parsed_msg firmware log parsed message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return message of the firmware log parsed message diff --git a/src/fw-logs/CMakeLists.txt b/src/fw-logs/CMakeLists.txt index 426bc350ad..87b93913e4 100644 --- a/src/fw-logs/CMakeLists.txt +++ b/src/fw-logs/CMakeLists.txt @@ -10,6 +10,6 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/fw-logs-parser.h" "${CMAKE_CURRENT_LIST_DIR}/fw-logs-xml-helper.cpp" "${CMAKE_CURRENT_LIST_DIR}/fw-logs-xml-helper.h" - "${CMAKE_CURRENT_LIST_DIR}/fw-string-formatter.cpp" - "${CMAKE_CURRENT_LIST_DIR}/fw-string-formatter.h" + "${CMAKE_CURRENT_LIST_DIR}/fw-string-formatter.cpp" + "${CMAKE_CURRENT_LIST_DIR}/fw-string-formatter.h" ) From f243dec18c68113e04460bf6050ad079a2894f40 Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 12:24:26 +0300 Subject: [PATCH 32/43] add fw and flash logs support for sr300 --- src/ivcam/sr300.cpp | 4 +++- src/ivcam/sr300.h | 8 +++++--- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/src/ivcam/sr300.cpp b/src/ivcam/sr300.cpp index 8329308522..ae052691f7 100644 --- a/src/ivcam/sr300.cpp +++ b/src/ivcam/sr300.cpp @@ -422,6 +422,7 @@ namespace librealsense const platform::backend_device_group& group, bool register_device_notifications) : device(ctx, group, register_device_notifications), + firmware_logger_device(_hw_monitor, get_depth_sensor()), _depth_device_idx(add_sensor(create_depth_device(ctx, depth))), _depth_stream(new stream(RS2_STREAM_DEPTH)), _ir_stream(new stream(RS2_STREAM_INFRARED)), @@ -492,7 +493,8 @@ namespace librealsense const platform::usb_device_info &hwm_device, const platform::backend_device_group& group, bool register_device_notifications) - : sr300_camera(ctx, color, depth, hwm_device, group, register_device_notifications) { + : sr300_camera(ctx, color, depth, hwm_device, group, register_device_notifications), + device(ctx, group, register_device_notifications) { static auto device_name = "Intel RealSense SR305"; update_info(RS2_CAMERA_INFO_NAME, device_name); diff --git a/src/ivcam/sr300.h b/src/ivcam/sr300.h index 094c47c954..8a88392d7b 100644 --- a/src/ivcam/sr300.h +++ b/src/ivcam/sr300.h @@ -21,6 +21,7 @@ #include "stream.h" #include "fw-update/fw-update-device-interface.h" #include "proc/color-formats-converter.h" +#include "firmware_logger_device.h" namespace librealsense { @@ -185,9 +186,10 @@ namespace librealsense platform::usb_device_info _hwm; }; - class sr300_camera : public device, - public debug_interface, - public updatable + class sr300_camera : public virtual device, + public debug_interface, + public updatable, + public firmware_logger_device { public: std::vector get_profiles_tags() const override From 6228b58a4089c4186c9c9559a303a700354734e7 Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 15:09:14 +0300 Subject: [PATCH 33/43] tabs and log removed --- include/CMakeLists.txt | 4 ++-- src/firmware_logger_device.cpp | 1 - 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index 46fcaed190..fff0107534 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -17,7 +17,7 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_pipeline.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_config.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_firmware_logs.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_terminal_parser.h" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_terminal_parser.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_types.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_context.hpp" @@ -32,7 +32,7 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_internal.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_pipeline.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_firmware_logs.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_terminal_parser.hpp" + "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_terminal_parser.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rsutil.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs_advanced_mode.h" diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index aa156ef531..c25a028964 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -117,7 +117,6 @@ namespace librealsense auto res = _hw_monitor->send(it->second.fw_logs_command); if (res.empty()) { - LOG_INFO("Getting Firmware logs failed!"); return; } From b4bda5c186397e9e50fe9f38e1da9a5e98498c55 Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 14:58:12 +0300 Subject: [PATCH 34/43] commands sent from each device ctor --- src/ds5/ds5-device.cpp | 10 ++++ src/ds5/ds5-device.h | 3 ++ src/ds5/ds5-factory.cpp | 73 +++++++++++++++++++------- src/firmware_logger_device.cpp | 96 ++-------------------------------- src/firmware_logger_device.h | 21 ++------ src/ivcam/sr300.cpp | 12 ++++- src/ivcam/sr300.h | 3 ++ src/l500/l500-device.cpp | 10 ++++ src/l500/l500-device.h | 3 ++ src/l500/l500-factory.cpp | 8 ++- 10 files changed, 109 insertions(+), 130 deletions(-) diff --git a/src/ds5/ds5-device.cpp b/src/ds5/ds5-device.cpp index bdde330540..756a7c52e3 100644 --- a/src/ds5/ds5-device.cpp +++ b/src/ds5/ds5-device.cpp @@ -945,6 +945,16 @@ namespace librealsense #endif } + command ds5_device::get_firmware_logs_command() const + { + return command{ ds::GLD, 0x1f4 }; + } + + command ds5_device::get_flash_logs_command() const + { + return command{ ds::FRB, 0x17a000, 0x3f8 }; + } + std::shared_ptr ds5u_device::create_ds5u_depth_device(std::shared_ptr ctx, const std::vector& all_device_infos) { diff --git a/src/ds5/ds5-device.h b/src/ds5/ds5-device.h index b4bb61dd35..ec1f8d3c64 100644 --- a/src/ds5/ds5-device.h +++ b/src/ds5/ds5-device.h @@ -75,6 +75,9 @@ namespace librealsense ds::d400_caps parse_device_capabilities(const uint16_t pid) const; + command get_firmware_logs_command() const; + command get_flash_logs_command() const; + void init(std::shared_ptr ctx, const platform::backend_device_group& group); diff --git a/src/ds5/ds5-factory.cpp b/src/ds5/ds5-factory.cpp index 64b3aa22da..e74059b0f5 100644 --- a/src/ds5/ds5-factory.cpp +++ b/src/ds5/ds5-factory.cpp @@ -39,7 +39,9 @@ namespace librealsense ds5_device(ctx, group), ds5_nonmonochrome(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -75,7 +77,9 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5u_device(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -127,7 +131,9 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -165,7 +171,9 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -203,7 +211,9 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -256,7 +266,9 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -306,7 +318,9 @@ namespace librealsense ds5_device(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -350,7 +364,9 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5_device(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -387,7 +403,9 @@ namespace librealsense ds5_device(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -425,7 +443,9 @@ namespace librealsense ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), ds5_motion(ctx, group), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::vector get_profiles_tags() const override @@ -467,7 +487,9 @@ namespace librealsense ds5_active(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -515,7 +537,9 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -556,7 +580,9 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -597,7 +623,9 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) { check_and_restore_rgb_stream_extrinsic(); } @@ -815,7 +843,9 @@ namespace librealsense ds5_motion(ctx, group), ds5_nonmonochrome(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -851,7 +881,9 @@ namespace librealsense ds5_device(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -881,8 +913,9 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) - {} + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -926,7 +959,9 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, get_depth_sensor()) + firmware_logger_device(ds5_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index c25a028964..0f97d06f09 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -9,76 +9,14 @@ namespace librealsense { - std::map - firmware_logger_device::_logs_commands_per_group = - { - {LOGS_COMMANDS_GROUP_DS, {command{ds::GLD, 0x1f4}, command{ds::FRB, 0x17a000, 0x3f8}}}, - {LOGS_COMMANDS_GROUP_L5, {command{ivcam2::GLD, 0x1f4}, command{ivcam2::FRB, 0x0011E000, 0x3f8}}}, - {LOGS_COMMANDS_GROUP_SR, {command{ivcam::GLD, 0x1f4}, command{ivcam::FlashRead, 0x000B6000, 0x3f8}}} - }; - - - firmware_logger_device::logs_commands_group firmware_logger_device::get_logs_commands_group(uint16_t device_pid) - { - logs_commands_group group = LOGS_COMMANDS_GROUP_NONE; - switch (device_pid) - { - case ds::RS400_PID: - case ds::RS410_PID: - case ds::RS415_PID: - case ds::RS430_PID: - case ds::RS430_MM_PID: - case ds::RS_USB2_PID: - case ds::RS_RECOVERY_PID: - case ds::RS_USB2_RECOVERY_PID: - case ds::RS400_IMU_PID: - case ds::RS420_PID: - case ds::RS420_MM_PID: - case ds::RS410_MM_PID: - case ds::RS400_MM_PID: - case ds::RS430_MM_RGB_PID: - case ds::RS460_PID: - case ds::RS435_RGB_PID: - case ds::RS405U_PID: - case ds::RS435I_PID: - case ds::RS416_PID: - case ds::RS430I_PID: - case ds::RS465_PID: - case ds::RS416_RGB_PID: - case ds::RS405_PID: - case ds::RS455_PID: - group = LOGS_COMMANDS_GROUP_DS; - break; - case L500_RECOVERY_PID: - case L500_PID: - case L515_PID_PRE_PRQ: - case L515_PID: - group = LOGS_COMMANDS_GROUP_L5; - break; - case SR300_PID: - case SR300v2_PID: - case SR300_RECOVERY: - group = LOGS_COMMANDS_GROUP_SR; - break; - default: - break; - } - return group; - } - firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, - const synthetic_sensor& depth_sensor) : + const command& fw_logs_command, const command& flash_logs_command) : _hw_monitor(hardware_monitor), _fw_logs(), _flash_logs(), _flash_logs_initialized(false), - _parser(nullptr) - { - std::string pid_str (depth_sensor.get_info(RS2_CAMERA_INFO_PRODUCT_ID)); - std::stringstream ss; - ss << std::hex << pid_str; - ss >> _device_pid; - } + _parser(nullptr), _fw_logs_command(fw_logs_command), + _flash_logs_command(flash_logs_command) { } bool firmware_logger_device::get_fw_log(fw_logs::fw_logs_binary_data& binary_data) { @@ -102,19 +40,7 @@ namespace librealsense void firmware_logger_device::get_fw_logs_from_hw_monitor() { - logs_commands_group group = get_logs_commands_group(_device_pid); - if (group == LOGS_COMMANDS_GROUP_NONE) - { - LOG_INFO("Firmware logs not set for this device!"); - return; - } - auto it = _logs_commands_per_group.find(group); - if (it == _logs_commands_per_group.end()) - { - LOG_INFO("Firmware logs not set for this device!"); - return; - } - auto res = _hw_monitor->send(it->second.fw_logs_command); + auto res = _hw_monitor->send(_fw_logs_command); if (res.empty()) { return; @@ -137,19 +63,7 @@ namespace librealsense void firmware_logger_device::get_flash_logs_from_hw_monitor() { - logs_commands_group group = get_logs_commands_group(_device_pid); - if (group == LOGS_COMMANDS_GROUP_NONE) - { - LOG_INFO("Flash logs not set for this device!"); - return; - } - auto it = _logs_commands_per_group.find(group); - if (it == _logs_commands_per_group.end()) - { - LOG_INFO("Flash logs not set for this device!"); - return; - } - auto res = _hw_monitor->send(it->second.flash_logs_command); + auto res = _hw_monitor->send(_flash_logs_command); if (res.empty()) { diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index dbe718d532..5e41ca17df 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -26,7 +26,7 @@ namespace librealsense { public: firmware_logger_device(std::shared_ptr hardware_monitor, - const synthetic_sensor& depth_sensor); + const command& _fw_logs_command, const command& _flash_logs_command); bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; @@ -35,26 +35,13 @@ namespace librealsense bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; private: - enum logs_commands_group - { - LOGS_COMMANDS_GROUP_NONE, - LOGS_COMMANDS_GROUP_DS, - LOGS_COMMANDS_GROUP_L5, - LOGS_COMMANDS_GROUP_SR, - LOGS_COMMANDS_GROUP_COUNT - }; - struct logs_commands - { - command fw_logs_command; - command flash_logs_command; - }; - static std::map _logs_commands_per_group; - - logs_commands_group get_logs_commands_group(uint16_t device_pid); void get_fw_logs_from_hw_monitor(); void get_flash_logs_from_hw_monitor(); + command _fw_logs_command; + command _flash_logs_command; + std::shared_ptr _hw_monitor; std::queue _fw_logs; diff --git a/src/ivcam/sr300.cpp b/src/ivcam/sr300.cpp index ae052691f7..e903b7bce1 100644 --- a/src/ivcam/sr300.cpp +++ b/src/ivcam/sr300.cpp @@ -422,7 +422,7 @@ namespace librealsense const platform::backend_device_group& group, bool register_device_notifications) : device(ctx, group, register_device_notifications), - firmware_logger_device(_hw_monitor, get_depth_sensor()), + firmware_logger_device(_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()), _depth_device_idx(add_sensor(create_depth_device(ctx, depth))), _depth_stream(new stream(RS2_STREAM_DEPTH)), _ir_stream(new stream(RS2_STREAM_INFRARED)), @@ -507,6 +507,16 @@ namespace librealsense } + command sr300_camera::get_firmware_logs_command() const + { + return command{ ivcam::GLD, 0x1f4 }; + } + + command sr300_camera::get_flash_logs_command() const + { + return command{ ivcam::FlashRead, 0x000B6000, 0x3f8 }; + } + void sr300_camera::create_snapshot(std::shared_ptr& snapshot) const { //TODO: implement diff --git a/src/ivcam/sr300.h b/src/ivcam/sr300.h index 8a88392d7b..c6a34bb319 100644 --- a/src/ivcam/sr300.h +++ b/src/ivcam/sr300.h @@ -534,6 +534,9 @@ namespace librealsense lazy _camer_calib_params; protected: + command get_firmware_logs_command() const; + command get_flash_logs_command() const; + const uint8_t _color_device_idx; std::shared_ptr _hw_monitor; }; diff --git a/src/l500/l500-device.cpp b/src/l500/l500-device.cpp index 9a1187f712..5833600580 100644 --- a/src/l500/l500-device.cpp +++ b/src/l500/l500-device.cpp @@ -467,6 +467,16 @@ namespace librealsense }); } + command l500_device::get_firmware_logs_command() const + { + return command{ ivcam2::GLD, 0x1f4 }; + } + + command l500_device::get_flash_logs_command() const + { + return command{ ivcam2::FRB, 0x0011E000, 0x3f8 }; + } + notification l500_notification_decoder::decode(int value) { if (l500_fw_error_report.find(static_cast(value)) != l500_fw_error_report.end()) diff --git a/src/l500/l500-device.h b/src/l500/l500-device.h index 73a62a1ab7..a01bda80a2 100644 --- a/src/l500/l500-device.h +++ b/src/l500/l500-device.h @@ -78,6 +78,9 @@ namespace librealsense void force_hardware_reset() const; bool _is_locked = true; + command get_firmware_logs_command() const; + command get_flash_logs_command() const; + std::vector _advanced_options; }; diff --git a/src/l500/l500-factory.cpp b/src/l500/l500-factory.cpp index 51297c5626..7bf33bd82e 100644 --- a/src/l500/l500-factory.cpp +++ b/src/l500/l500-factory.cpp @@ -42,7 +42,9 @@ namespace librealsense l500_color(ctx, group), l500_motion(ctx, group), l500_serializable(l500_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(l500_device::_hw_monitor, get_depth_sensor()) + firmware_logger_device(l500_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; @@ -72,7 +74,9 @@ namespace librealsense : device(ctx, group, register_device_notifications), l500_device(ctx, group), l500_depth(ctx, group), - firmware_logger_device(l500_device::_hw_monitor, get_depth_sensor()) + firmware_logger_device(l500_device::_hw_monitor, + get_firmware_logs_command(), + get_flash_logs_command()) {} std::shared_ptr create_matcher(const frame_holder& frame) const override; From 76470ea37958533cf7961c16c2f07686b42bf191 Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 15:13:54 +0300 Subject: [PATCH 35/43] rs-fw-logger code correction --- tools/fw-logger/rs-fw-logger.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/fw-logger/rs-fw-logger.cpp b/tools/fw-logger/rs-fw-logger.cpp index 4838cdc524..79ba9b656c 100644 --- a/tools/fw-logger/rs-fw-logger.cpp +++ b/tools/fw-logger/rs-fw-logger.cpp @@ -132,7 +132,7 @@ int main(int argc, char* argv[]) std::vector msg_data = log_message.data(); for (int i = 0; i < msg_data.size(); ++i) { - sstr << char2hex(raw_data[i]) << " "; + sstr << char2hex(msg_data[i]) << " "; } fw_log_lines.push_back(sstr.str()); } From 4d645d6ef9a73d241d5dd93dee1d36d35e756cce Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 15:23:52 +0300 Subject: [PATCH 36/43] remove unnecessary includes --- src/firmware_logger_device.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 0f97d06f09..ef53d64c15 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -2,9 +2,6 @@ // Copyright(c) 2020 Intel Corporation. All Rights Reserved. #include "firmware_logger_device.h" -#include "ds5/ds5-private.h" -#include "l500/l500-private.h" -#include "ivcam/sr300.h" #include namespace librealsense From d32d694fb26bdd0fe894b46f620011f9cae4e4ae Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 15:56:02 +0300 Subject: [PATCH 37/43] moving api code of fw logs and terminal_parser to rs_internal --- include/CMakeLists.txt | 4 - include/librealsense2/h/rs_firmware_logs.h | 175 ------------- include/librealsense2/h/rs_internal.h | 195 ++++++++++++++ include/librealsense2/h/rs_terminal_parser.h | 63 ----- .../librealsense2/hpp/rs_firmware_logs.hpp | 203 -------------- include/librealsense2/hpp/rs_internal.hpp | 247 ++++++++++++++++++ .../librealsense2/hpp/rs_terminal_parser.hpp | 76 ------ include/librealsense2/rs.h | 2 - include/librealsense2/rs.hpp | 2 - src/ds5/ds5-device.h | 1 + src/ivcam/sr300.h | 2 + src/l500/l500-device.h | 1 + tools/fw-logger/rs-fw-logger.cpp | 3 +- 13 files changed, 448 insertions(+), 526 deletions(-) delete mode 100644 include/librealsense2/h/rs_firmware_logs.h delete mode 100644 include/librealsense2/h/rs_terminal_parser.h delete mode 100644 include/librealsense2/hpp/rs_firmware_logs.hpp delete mode 100644 include/librealsense2/hpp/rs_terminal_parser.hpp diff --git a/include/CMakeLists.txt b/include/CMakeLists.txt index fff0107534..81d8cdc93c 100644 --- a/include/CMakeLists.txt +++ b/include/CMakeLists.txt @@ -16,8 +16,6 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_internal.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_pipeline.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_config.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_firmware_logs.h" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/h/rs_terminal_parser.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_types.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_context.hpp" @@ -31,8 +29,6 @@ target_sources(${LRS_TARGET} "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_options.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_internal.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_pipeline.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_firmware_logs.hpp" - "${CMAKE_CURRENT_LIST_DIR}/librealsense2/hpp/rs_terminal_parser.hpp" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rsutil.h" "${CMAKE_CURRENT_LIST_DIR}/librealsense2/rs_advanced_mode.h" diff --git a/include/librealsense2/h/rs_firmware_logs.h b/include/librealsense2/h/rs_firmware_logs.h deleted file mode 100644 index 9ad98a17fd..0000000000 --- a/include/librealsense2/h/rs_firmware_logs.h +++ /dev/null @@ -1,175 +0,0 @@ -/* License: Apache 2.0. See LICENSE file in root directory. - Copyright(c) 2020 Intel Corporation. All Rights Reserved. */ - -/** \file rs_firmware_logs.h -* \brief Exposes RealSense firmware logs functionality for C compilers -*/ - - -#ifndef LIBREALSENSE_RS2_FIRMWARE_LOGS_H -#define LIBREALSENSE_RS2_FIRMWARE_LOGS_H - -#ifdef __cplusplus -extern "C" { -#endif - -#include "rs_types.h" - -/** -* \brief Creates RealSense firmware log message. -* \param[in] dev Device from which the FW log will be taken using the created message -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return pointer to created empty firmware log message -*/ -rs2_firmware_log_message* rs2_create_fw_log_message(rs2_device* dev, rs2_error** error); - -/** -* \brief Gets RealSense firmware log. -* \param[in] dev Device from which the FW log should be taken -* \param[in] fw_log_msg Firmware log message object to be filled -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor -*/ -int rs2_get_fw_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); - -/** -* \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device -* \param[in] dev Device from which the FW log should be taken -* \param[in] fw_log_msg Firmware log message object to be filled -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor -*/ -int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); - -/** -* Delete RealSense firmware log message -* \param[in] device Realsense firmware log message to delete -*/ -void rs2_delete_fw_log_message(rs2_firmware_log_message* msg); - -/** -* \brief Gets RealSense firmware log message data. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return pointer to start of the firmware log message data -*/ -const unsigned char* rs2_fw_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log message size. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return size of the firmware log message data -*/ -int rs2_fw_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); - - -/** -* \brief Gets RealSense firmware log message timestamp. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return timestamp of the firmware log message -*/ -unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log message severity. -* \param[in] msg firmware log message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return severity of the firmware log message data -*/ -rs2_log_severity rs2_fw_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); - -/** -* \brief Initializes RealSense firmware logs parser in device. -* \param[in] dev Device from which the FW log will be taken -* \param[in] xml_content content of the xml file needed for parsing -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails -*/ -int rs2_init_fw_log_parser(rs2_device* dev, const char* xml_content, rs2_error** error); - - -/** -* \brief Creates RealSense firmware log parsed message. -* \param[in] dev Device from which the FW log will be taken using the created message -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return pointer to created empty firmware log message -*/ -rs2_firmware_log_parsed_message* rs2_create_fw_log_parsed_message(rs2_device* dev, rs2_error** error); - -/** -* \brief Deletes RealSense firmware log parsed message. -* \param[in] msg message to be deleted -*/ -void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); - - -/** -* \brief Gets RealSense firmware log parser -* \param[in] dev Device from which the FW log will be taken -* \param[in] fw_log_msg firmware log message to be parsed -* \param[in] parsed_msg firmware log parsed message - place holder for the resulting parsed message -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return true for success, false for failure - failure happens if message could not be parsed -*/ -int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_firmware_log_parsed_message* parsed_msg, rs2_error** error); - -/** -* Delete RealSense firmware log parsed message -* \param[in] device Realsense firmware log parsed message to delete -*/ -void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); - -/** -* \brief Gets RealSense firmware log parsed message. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return message of the firmware log parsed message -*/ -const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message file name. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return file name of the firmware log parsed message -*/ -const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message thread name. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return thread name of the firmware log parsed message -*/ -const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message severity. -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return severity of the firmware log parsed message -*/ -rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_log_parsed_file_name). -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return line number of the firmware log parsed message -*/ -unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -/** -* \brief Gets RealSense firmware log parsed message timestamp -* \param[in] fw_log_parsed_msg firmware log parsed message object -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return timestamp of the firmware log parsed message -*/ -unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); - -#ifdef __cplusplus -} -#endif -#endif diff --git a/include/librealsense2/h/rs_internal.h b/include/librealsense2/h/rs_internal.h index 3fe6bdcbb0..b5150507b7 100644 --- a/include/librealsense2/h/rs_internal.h +++ b/include/librealsense2/h/rs_internal.h @@ -347,6 +347,201 @@ void rs2_software_sensor_add_option(rs2_sensor* sensor, rs2_option option, float */ void rs2_software_sensor_detach(rs2_sensor* sensor, rs2_error** error); + +/** +* \brief Creates RealSense firmware log message. +* \param[in] dev Device from which the FW log will be taken using the created message +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to created empty firmware log message +*/ +rs2_firmware_log_message* rs2_create_fw_log_message(rs2_device* dev, rs2_error** error); + +/** +* \brief Gets RealSense firmware log. +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor +*/ +int rs2_get_fw_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); + +/** +* \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor +*/ +int rs2_get_flash_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_error** error); + +/** +* Delete RealSense firmware log message +* \param[in] device Realsense firmware log message to delete +*/ +void rs2_delete_fw_log_message(rs2_firmware_log_message* msg); + +/** +* \brief Gets RealSense firmware log message data. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to start of the firmware log message data +*/ +const unsigned char* rs2_fw_log_message_data(rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log message size. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return size of the firmware log message data +*/ +int rs2_fw_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); + + +/** +* \brief Gets RealSense firmware log message timestamp. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return timestamp of the firmware log message +*/ +unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log message severity. +* \param[in] msg firmware log message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return severity of the firmware log message data +*/ +rs2_log_severity rs2_fw_log_message_severity(const rs2_firmware_log_message* msg, rs2_error** error); + +/** +* \brief Initializes RealSense firmware logs parser in device. +* \param[in] dev Device from which the FW log will be taken +* \param[in] xml_content content of the xml file needed for parsing +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails +*/ +int rs2_init_fw_log_parser(rs2_device* dev, const char* xml_content, rs2_error** error); + + +/** +* \brief Creates RealSense firmware log parsed message. +* \param[in] dev Device from which the FW log will be taken using the created message +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to created empty firmware log message +*/ +rs2_firmware_log_parsed_message* rs2_create_fw_log_parsed_message(rs2_device* dev, rs2_error** error); + +/** +* \brief Deletes RealSense firmware log parsed message. +* \param[in] msg message to be deleted +*/ +void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); + + +/** +* \brief Gets RealSense firmware log parser +* \param[in] dev Device from which the FW log will be taken +* \param[in] fw_log_msg firmware log message to be parsed +* \param[in] parsed_msg firmware log parsed message - place holder for the resulting parsed message +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return true for success, false for failure - failure happens if message could not be parsed +*/ +int rs2_parse_firmware_log(rs2_device* dev, rs2_firmware_log_message* fw_log_msg, rs2_firmware_log_parsed_message* parsed_msg, rs2_error** error); + +/** +* Delete RealSense firmware log parsed message +* \param[in] device Realsense firmware log parsed message to delete +*/ +void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); + +/** +* \brief Gets RealSense firmware log parsed message. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return message of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message file name. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return file name of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message thread name. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return thread name of the firmware log parsed message +*/ +const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message severity. +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return severity of the firmware log parsed message +*/ +rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_log_parsed_file_name). +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return line number of the firmware log parsed message +*/ +unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Gets RealSense firmware log parsed message timestamp +* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return timestamp of the firmware log parsed message +*/ +unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw_log_parsed_msg, rs2_error** error); + +/** +* \brief Creates RealSense terminal parser. +* \param[in] xml_content content of the xml file needed for parsing +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return pointer to created terminal parser object +*/ +rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error); + +/** +* \brief Deletes RealSense terminal parser. +* \param[in] terminal_parser terminal parser to be deleted +*/ +void rs2_delete_terminal_parser(rs2_terminal_parser* terminal_parser); + +/** +* \brief Parses terminal command via RealSense terminal parser +* \param[in] terminal_parser Terminal parser object +* \param[in] command command to be sent to the hw monitor of the device +* \param[in] size_of_command size of command to be sent to the hw monitor of the device +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return command to hw monitor, in hex +*/ +rs2_raw_data_buffer* rs2_terminal_parse_command(rs2_terminal_parser* terminal_parser, + const char* command, unsigned int size_of_command, rs2_error** error); + +/** +* \brief Parses terminal response via RealSense terminal parser +* \param[in] terminal_parser Terminal parser object +* \param[in] command command sent to the hw monitor of the device +* \param[in] size_of_command size of the command to sent to the hw monitor of the device +* \param[in] response response received by the hw monitor of the device +* \param[in] size_of_response size of the response received by the hw monitor of the device +* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. +* \return answer parsed +*/ +rs2_raw_data_buffer* rs2_terminal_parse_response(rs2_terminal_parser* terminal_parser, + const char* command, unsigned int size_of_command, + const void* response, unsigned int size_of_response, rs2_error** error); + + #ifdef __cplusplus } #endif diff --git a/include/librealsense2/h/rs_terminal_parser.h b/include/librealsense2/h/rs_terminal_parser.h deleted file mode 100644 index 3bb9239c9e..0000000000 --- a/include/librealsense2/h/rs_terminal_parser.h +++ /dev/null @@ -1,63 +0,0 @@ -/* License: Apache 2.0. See LICENSE file in root directory. - Copyright(c) 2020 Intel Corporation. All Rights Reserved. */ - -/** \file rs_terminal.h -* \brief Exposes RealSense terminal functionality for C compilers -*/ - - -#ifndef LIBREALSENSE_RS2_TERMINAL_H -#define LIBREALSENSE_RS2_TERMINAL_H - -#ifdef __cplusplus -extern "C" { -#endif - -#include "rs_types.h" - -/** -* \brief Creates RealSense terminal parser. -* \param[in] xml_content content of the xml file needed for parsing -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return pointer to created terminal parser object -*/ -rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_error** error); - -/** -* \brief Deletes RealSense terminal parser. -* \param[in] terminal_parser terminal parser to be deleted -*/ -void rs2_delete_terminal_parser(rs2_terminal_parser* terminal_parser); - -/** -* \brief Parses terminal command via RealSense terminal parser -* \param[in] terminal_parser Terminal parser object -* \param[in] command command to be sent to the hw monitor of the device -* \param[in] size_of_command size of command to be sent to the hw monitor of the device -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return command to hw monitor, in hex -*/ -rs2_raw_data_buffer* rs2_terminal_parse_command(rs2_terminal_parser* terminal_parser, - const char* command, unsigned int size_of_command, rs2_error** error); - -/** -* \brief Parses terminal response via RealSense terminal parser -* \param[in] terminal_parser Terminal parser object -* \param[in] command command sent to the hw monitor of the device -* \param[in] size_of_command size of the command to sent to the hw monitor of the device -* \param[in] response response received by the hw monitor of the device -* \param[in] size_of_response size of the response received by the hw monitor of the device -* \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. -* \return answer parsed -*/ -rs2_raw_data_buffer* rs2_terminal_parse_response(rs2_terminal_parser* terminal_parser, - const char* command, unsigned int size_of_command, - const void* response, unsigned int size_of_response, rs2_error** error); - - - - -#ifdef __cplusplus -} -#endif -#endif diff --git a/include/librealsense2/hpp/rs_firmware_logs.hpp b/include/librealsense2/hpp/rs_firmware_logs.hpp deleted file mode 100644 index 1b1d005ba1..0000000000 --- a/include/librealsense2/hpp/rs_firmware_logs.hpp +++ /dev/null @@ -1,203 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2020 Intel Corporation. All Rights Reserved. - -#ifndef LIBREALSENSE_RS2_FIRMWARE_LOGS_HPP -#define LIBREALSENSE_RS2_FIRMWARE_LOGS_HPP - -#include "rs_types.hpp" -#include "rs_sensor.hpp" -#include "../h/rs_firmware_logs.h" - -namespace rs2 -{ - class firmware_log_message - { - public: - explicit firmware_log_message(std::shared_ptr msg): - _fw_log_message(msg){} - - rs2_log_severity get_severity() const { - rs2_error* e = nullptr; - rs2_log_severity severity = rs2_fw_log_message_severity(_fw_log_message.get(), &e); - error::handle(e); - return severity; - } - std::string get_severity_str() const { - return rs2_log_severity_to_string(get_severity()); - } - - uint32_t get_timestamp() const - { - rs2_error* e = nullptr; - uint32_t timestamp = rs2_fw_log_message_timestamp(_fw_log_message.get(), &e); - error::handle(e); - return timestamp; - } - - int size() const - { - rs2_error* e = nullptr; - int size = rs2_fw_log_message_size(_fw_log_message.get(), &e); - error::handle(e); - return size; - } - - std::vector data() const - { - rs2_error* e = nullptr; - auto size = rs2_fw_log_message_size(_fw_log_message.get(), &e); - error::handle(e); - std::vector result; - if (size > 0) - { - auto start = rs2_fw_log_message_data(_fw_log_message.get(), &e); - error::handle(e); - result.insert(result.begin(), start, start + size); - } - return result; - } - - const std::shared_ptr get_message() const { return _fw_log_message; } - - private: - std::shared_ptr _fw_log_message; - }; - - class firmware_log_parsed_message - { - public: - explicit firmware_log_parsed_message(std::shared_ptr msg) : - _parsed_fw_log(msg) {} - - std::string message() const - { - rs2_error* e = nullptr; - std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e)); - error::handle(e); - return msg; - } - std::string file_name() const - { - rs2_error* e = nullptr; - std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e)); - error::handle(e); - return file_name; - } - std::string thread_name() const - { - rs2_error* e = nullptr; - std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e)); - error::handle(e); - return thread_name; - } - std::string severity() const - { - rs2_error* e = nullptr; - rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e); - error::handle(e); - return std::string(rs2_log_severity_to_string(sev)); - } - uint32_t line() const - { - rs2_error* e = nullptr; - uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e)); - error::handle(e); - return line; - } - uint32_t timestamp() const - { - rs2_error* e = nullptr; - uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e)); - error::handle(e); - return timestamp; - } - - const std::shared_ptr get_message() const { return _parsed_fw_log; } - - private: - std::shared_ptr _parsed_fw_log; - }; - - class firmware_logger : public device - { - public: - firmware_logger(device d) - : device(d.get()) - { - rs2_error* e = nullptr; - if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_FW_LOGGER, &e) == 0 && !e) - { - _dev.reset(); - } - error::handle(e); - } - - rs2::firmware_log_message create_message() - { - rs2_error* e = nullptr; - std::shared_ptr msg( - rs2_create_fw_log_message(_dev.get(), &e), - rs2_delete_fw_log_message); - error::handle(e); - - return firmware_log_message(msg); - } - - rs2::firmware_log_parsed_message create_parsed_message() - { - rs2_error* e = nullptr; - std::shared_ptr msg( - rs2_create_fw_log_parsed_message(_dev.get(), &e), - rs2_delete_fw_log_parsed_message); - error::handle(e); - - return firmware_log_parsed_message(msg); - } - - bool get_firmware_log(rs2::firmware_log_message& msg) const - { - rs2_error* e = nullptr; - rs2_firmware_log_message* m = msg.get_message().get(); - bool fw_log_pulling_status = - rs2_get_fw_log(_dev.get(), &(m), &e); - - error::handle(e); - - return fw_log_pulling_status; - } - - bool get_flash_log(rs2::firmware_log_message& msg) const - { - rs2_error* e = nullptr; - rs2_firmware_log_message* m = msg.get_message().get(); - bool flash_log_pulling_status = - rs2_get_flash_log(_dev.get(), &(m), &e); - - error::handle(e); - - return flash_log_pulling_status; - } - - bool init_parser(const std::string& xml_content) - { - rs2_error* e = nullptr; - - bool parser_initialized = rs2_init_fw_log_parser(_dev.get(), xml_content.c_str(), &e); - error::handle(e); - - return parser_initialized; - } - - bool parse_log(const rs2::firmware_log_message& msg, const rs2::firmware_log_parsed_message& parsed_msg) - { - rs2_error* e = nullptr; - - bool parsingResult = rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), parsed_msg.get_message().get(), &e); - error::handle(e); - - return parsingResult; - } - }; - -} -#endif // LIBREALSENSE_RS2_FIRMWARE_LOGS_HPP diff --git a/include/librealsense2/hpp/rs_internal.hpp b/include/librealsense2/hpp/rs_internal.hpp index 076a49c6a0..116449b2c9 100644 --- a/include/librealsense2/hpp/rs_internal.hpp +++ b/include/librealsense2/hpp/rs_internal.hpp @@ -363,5 +363,252 @@ namespace rs2 } }; + class firmware_log_message + { + public: + explicit firmware_log_message(std::shared_ptr msg) : + _fw_log_message(msg) {} + + rs2_log_severity get_severity() const { + rs2_error* e = nullptr; + rs2_log_severity severity = rs2_fw_log_message_severity(_fw_log_message.get(), &e); + error::handle(e); + return severity; + } + std::string get_severity_str() const { + return rs2_log_severity_to_string(get_severity()); + } + + uint32_t get_timestamp() const + { + rs2_error* e = nullptr; + uint32_t timestamp = rs2_fw_log_message_timestamp(_fw_log_message.get(), &e); + error::handle(e); + return timestamp; + } + + int size() const + { + rs2_error* e = nullptr; + int size = rs2_fw_log_message_size(_fw_log_message.get(), &e); + error::handle(e); + return size; + } + + std::vector data() const + { + rs2_error* e = nullptr; + auto size = rs2_fw_log_message_size(_fw_log_message.get(), &e); + error::handle(e); + std::vector result; + if (size > 0) + { + auto start = rs2_fw_log_message_data(_fw_log_message.get(), &e); + error::handle(e); + result.insert(result.begin(), start, start + size); + } + return result; + } + + const std::shared_ptr get_message() const { return _fw_log_message; } + + private: + std::shared_ptr _fw_log_message; + }; + + class firmware_log_parsed_message + { + public: + explicit firmware_log_parsed_message(std::shared_ptr msg) : + _parsed_fw_log(msg) {} + + std::string message() const + { + rs2_error* e = nullptr; + std::string msg(rs2_get_fw_log_parsed_message(_parsed_fw_log.get(), &e)); + error::handle(e); + return msg; + } + std::string file_name() const + { + rs2_error* e = nullptr; + std::string file_name(rs2_get_fw_log_parsed_file_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return file_name; + } + std::string thread_name() const + { + rs2_error* e = nullptr; + std::string thread_name(rs2_get_fw_log_parsed_thread_name(_parsed_fw_log.get(), &e)); + error::handle(e); + return thread_name; + } + std::string severity() const + { + rs2_error* e = nullptr; + rs2_log_severity sev = rs2_get_fw_log_parsed_severity(_parsed_fw_log.get(), &e); + error::handle(e); + return std::string(rs2_log_severity_to_string(sev)); + } + uint32_t line() const + { + rs2_error* e = nullptr; + uint32_t line(rs2_get_fw_log_parsed_line(_parsed_fw_log.get(), &e)); + error::handle(e); + return line; + } + uint32_t timestamp() const + { + rs2_error* e = nullptr; + uint32_t timestamp(rs2_get_fw_log_parsed_timestamp(_parsed_fw_log.get(), &e)); + error::handle(e); + return timestamp; + } + + const std::shared_ptr get_message() const { return _parsed_fw_log; } + + private: + std::shared_ptr _parsed_fw_log; + }; + + class firmware_logger : public device + { + public: + firmware_logger(device d) + : device(d.get()) + { + rs2_error* e = nullptr; + if (rs2_is_device_extendable_to(_dev.get(), RS2_EXTENSION_FW_LOGGER, &e) == 0 && !e) + { + _dev.reset(); + } + error::handle(e); + } + + rs2::firmware_log_message create_message() + { + rs2_error* e = nullptr; + std::shared_ptr msg( + rs2_create_fw_log_message(_dev.get(), &e), + rs2_delete_fw_log_message); + error::handle(e); + + return firmware_log_message(msg); + } + + rs2::firmware_log_parsed_message create_parsed_message() + { + rs2_error* e = nullptr; + std::shared_ptr msg( + rs2_create_fw_log_parsed_message(_dev.get(), &e), + rs2_delete_fw_log_parsed_message); + error::handle(e); + + return firmware_log_parsed_message(msg); + } + + bool get_firmware_log(rs2::firmware_log_message& msg) const + { + rs2_error* e = nullptr; + rs2_firmware_log_message* m = msg.get_message().get(); + bool fw_log_pulling_status = + rs2_get_fw_log(_dev.get(), &(m), &e); + + error::handle(e); + + return fw_log_pulling_status; + } + + bool get_flash_log(rs2::firmware_log_message& msg) const + { + rs2_error* e = nullptr; + rs2_firmware_log_message* m = msg.get_message().get(); + bool flash_log_pulling_status = + rs2_get_flash_log(_dev.get(), &(m), &e); + + error::handle(e); + + return flash_log_pulling_status; + } + + bool init_parser(const std::string& xml_content) + { + rs2_error* e = nullptr; + + bool parser_initialized = rs2_init_fw_log_parser(_dev.get(), xml_content.c_str(), &e); + error::handle(e); + + return parser_initialized; + } + + bool parse_log(const rs2::firmware_log_message& msg, const rs2::firmware_log_parsed_message& parsed_msg) + { + rs2_error* e = nullptr; + + bool parsingResult = rs2_parse_firmware_log(_dev.get(), msg.get_message().get(), parsed_msg.get_message().get(), &e); + error::handle(e); + + return parsingResult; + } + }; + + class terminal_parser + { + public: + terminal_parser(const std::string& xml_content) + { + rs2_error* e = nullptr; + + _terminal_parser = std::shared_ptr( + rs2_create_terminal_parser(xml_content.c_str(), &e), + rs2_delete_terminal_parser); + error::handle(e); + } + + std::vector parse_command(const std::string& command) + { + rs2_error* e = nullptr; + + std::shared_ptr list( + rs2_terminal_parse_command(_terminal_parser.get(), command.c_str(), command.size(), &e), + rs2_delete_raw_data); + error::handle(e); + + auto size = rs2_get_raw_data_size(list.get(), &e); + error::handle(e); + + auto start = rs2_get_raw_data(list.get(), &e); + + std::vector results; + results.insert(results.begin(), start, start + size); + + return results; + } + + std::string parse_response(const std::string& command, const std::vector& response) + { + rs2_error* e = nullptr; + + std::shared_ptr list( + rs2_terminal_parse_response(_terminal_parser.get(), command.c_str(), command.size(), + (void*)response.data(), response.size(), &e), + rs2_delete_raw_data); + error::handle(e); + + auto size = rs2_get_raw_data_size(list.get(), &e); + error::handle(e); + + auto start = rs2_get_raw_data(list.get(), &e); + + std::string results; + results.insert(results.begin(), start, start + size); + + return results; + } + + private: + std::shared_ptr _terminal_parser; + }; + } #endif // LIBREALSENSE_RS2_INTERNAL_HPP diff --git a/include/librealsense2/hpp/rs_terminal_parser.hpp b/include/librealsense2/hpp/rs_terminal_parser.hpp deleted file mode 100644 index 45ecf6c608..0000000000 --- a/include/librealsense2/hpp/rs_terminal_parser.hpp +++ /dev/null @@ -1,76 +0,0 @@ -// License: Apache 2.0. See LICENSE file in root directory. -// Copyright(c) 2020 Intel Corporation. All Rights Reserved. - -#ifndef LIBREALSENSE_RS2_TERMINAL_PARSER_HPP -#define LIBREALSENSE_RS2_TERMINAL_PARSER_HPP - -#include "rs_types.hpp" -#include "rs_sensor.hpp" -#include "rs_device.hpp" - -#include -#include - -namespace rs2 -{ - class terminal_parser - { - public: - terminal_parser(const std::string& xml_content) - { - rs2_error* e = nullptr; - - _terminal_parser = std::shared_ptr( - rs2_create_terminal_parser(xml_content.c_str(), &e), - rs2_delete_terminal_parser); - error::handle(e); - } - - std::vector parse_command(const std::string& command) - { - rs2_error* e = nullptr; - - std::shared_ptr list( - rs2_terminal_parse_command(_terminal_parser.get(), command.c_str(), command.size(), &e), - rs2_delete_raw_data); - error::handle(e); - - auto size = rs2_get_raw_data_size(list.get(), &e); - error::handle(e); - - auto start = rs2_get_raw_data(list.get(), &e); - - std::vector results; - results.insert(results.begin(), start, start + size); - - return results; - } - - std::string parse_response(const std::string& command, const std::vector& response) - { - rs2_error* e = nullptr; - - std::shared_ptr list( - rs2_terminal_parse_response(_terminal_parser.get(), command.c_str(), command.size(), - (void*)response.data(), response.size(), &e), - rs2_delete_raw_data); - error::handle(e); - - auto size = rs2_get_raw_data_size(list.get(), &e); - error::handle(e); - - auto start = rs2_get_raw_data(list.get(), &e); - - std::string results; - results.insert(results.begin(), start, start + size); - - return results; - } - - private: - std::shared_ptr _terminal_parser; - }; -} - - -#endif // LIBREALSENSE_RS2_TYPES_HPP diff --git a/include/librealsense2/rs.h b/include/librealsense2/rs.h index dfb29974d8..6976fff839 100644 --- a/include/librealsense2/rs.h +++ b/include/librealsense2/rs.h @@ -21,8 +21,6 @@ extern "C" { #include "h/rs_processing.h" #include "h/rs_record_playback.h" #include "h/rs_sensor.h" -#include "h/rs_firmware_logs.h" -#include "h/rs_terminal_parser.h" #define RS2_API_MAJOR_VERSION 2 #define RS2_API_MINOR_VERSION 35 diff --git a/include/librealsense2/rs.hpp b/include/librealsense2/rs.hpp index b41366102d..2a9ee2e334 100644 --- a/include/librealsense2/rs.hpp +++ b/include/librealsense2/rs.hpp @@ -13,8 +13,6 @@ #include "hpp/rs_record_playback.hpp" #include "hpp/rs_sensor.hpp" #include "hpp/rs_pipeline.hpp" -#include "hpp/rs_firmware_logs.hpp" -#include "hpp/rs_terminal_parser.hpp" namespace rs2 { diff --git a/src/ds5/ds5-device.h b/src/ds5/ds5-device.h index ec1f8d3c64..edb821d1d5 100644 --- a/src/ds5/ds5-device.h +++ b/src/ds5/ds5-device.h @@ -75,6 +75,7 @@ namespace librealsense ds::d400_caps parse_device_capabilities(const uint16_t pid) const; + //TODO - add these to device class as pure virtual methods command get_firmware_logs_command() const; command get_flash_logs_command() const; diff --git a/src/ivcam/sr300.h b/src/ivcam/sr300.h index c6a34bb319..8454baad62 100644 --- a/src/ivcam/sr300.h +++ b/src/ivcam/sr300.h @@ -534,6 +534,8 @@ namespace librealsense lazy _camer_calib_params; protected: + + //TODO - add these to device class as pure virtual methods command get_firmware_logs_command() const; command get_flash_logs_command() const; diff --git a/src/l500/l500-device.h b/src/l500/l500-device.h index a01bda80a2..44f3aa2e90 100644 --- a/src/l500/l500-device.h +++ b/src/l500/l500-device.h @@ -78,6 +78,7 @@ namespace librealsense void force_hardware_reset() const; bool _is_locked = true; + //TODO - add these to device class as pure virtual methods command get_firmware_logs_command() const; command get_flash_logs_command() const; diff --git a/tools/fw-logger/rs-fw-logger.cpp b/tools/fw-logger/rs-fw-logger.cpp index 79ba9b656c..53c29c60df 100644 --- a/tools/fw-logger/rs-fw-logger.cpp +++ b/tools/fw-logger/rs-fw-logger.cpp @@ -1,7 +1,8 @@ // License: Apache 2.0. See LICENSE file in root directory. // Copyright(c) 2015 Intel Corporation. All Rights Reserved. -#include +#include "librealsense2\rs.hpp" +#include "librealsense2\hpp\rs_internal.hpp" #include #include #include "tclap/CmdLine.h" From ac54c4e86afa98ec88a076d88f5e8ebcf3915b95 Mon Sep 17 00:00:00 2001 From: remibettan Date: Thu, 18 Jun 2020 22:35:28 +0300 Subject: [PATCH 38/43] correcting slash directions --- tools/fw-logger/rs-fw-logger.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tools/fw-logger/rs-fw-logger.cpp b/tools/fw-logger/rs-fw-logger.cpp index 53c29c60df..6085f86ba5 100644 --- a/tools/fw-logger/rs-fw-logger.cpp +++ b/tools/fw-logger/rs-fw-logger.cpp @@ -1,8 +1,8 @@ // License: Apache 2.0. See LICENSE file in root directory. // Copyright(c) 2015 Intel Corporation. All Rights Reserved. -#include "librealsense2\rs.hpp" -#include "librealsense2\hpp\rs_internal.hpp" +#include "librealsense2/rs.hpp" +#include "librealsense2/hpp/rs_internal.hpp" #include #include #include "tclap/CmdLine.h" From ea05d7f8464a272c6e5da379555c6ef7d54ce861 Mon Sep 17 00:00:00 2001 From: remibettan Date: Sun, 21 Jun 2020 09:13:27 +0300 Subject: [PATCH 39/43] fix linux build --- src/ds5/ds5-factory.cpp | 36 +++++++++++++++++----------------- src/firmware_logger_device.cpp | 8 ++++++-- src/firmware_logger_device.h | 5 +++-- src/ivcam/sr300.cpp | 2 +- src/l500/l500-factory.cpp | 4 ++-- 5 files changed, 30 insertions(+), 25 deletions(-) diff --git a/src/ds5/ds5-factory.cpp b/src/ds5/ds5-factory.cpp index e74059b0f5..90d84d934e 100644 --- a/src/ds5/ds5-factory.cpp +++ b/src/ds5/ds5-factory.cpp @@ -39,7 +39,7 @@ namespace librealsense ds5_device(ctx, group), ds5_nonmonochrome(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -77,7 +77,7 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5u_device(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -131,7 +131,7 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -171,7 +171,7 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -211,7 +211,7 @@ namespace librealsense ds5_nonmonochrome(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -266,7 +266,7 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -318,7 +318,7 @@ namespace librealsense ds5_device(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -364,7 +364,7 @@ namespace librealsense : device(ctx, group, register_device_notifications), ds5_device(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -403,7 +403,7 @@ namespace librealsense ds5_device(ctx, group), ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -443,7 +443,7 @@ namespace librealsense ds5_active(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), ds5_motion(ctx, group), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -487,7 +487,7 @@ namespace librealsense ds5_active(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -537,7 +537,7 @@ namespace librealsense ds5_active(ctx, group), ds5_color(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -580,7 +580,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -623,7 +623,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) { @@ -843,7 +843,7 @@ namespace librealsense ds5_motion(ctx, group), ds5_nonmonochrome(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -881,7 +881,7 @@ namespace librealsense ds5_device(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -913,7 +913,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -959,7 +959,7 @@ namespace librealsense ds5_color(ctx, group), ds5_motion(ctx, group), ds5_advanced_mode_base(ds5_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(ds5_device::_hw_monitor, + firmware_logger_device(ctx, group, ds5_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index ef53d64c15..647c699c67 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -6,13 +6,17 @@ namespace librealsense { - firmware_logger_device::firmware_logger_device(std::shared_ptr hardware_monitor, + firmware_logger_device::firmware_logger_device(std::shared_ptr ctx, + const platform::backend_device_group group, + std::shared_ptr hardware_monitor, const command& fw_logs_command, const command& flash_logs_command) : + device(ctx, group), _hw_monitor(hardware_monitor), _fw_logs(), _flash_logs(), _flash_logs_initialized(false), - _parser(nullptr), _fw_logs_command(fw_logs_command), + _parser(nullptr), + _fw_logs_command(fw_logs_command), _flash_logs_command(flash_logs_command) { } bool firmware_logger_device::get_fw_log(fw_logs::fw_logs_binary_data& binary_data) diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 5e41ca17df..7634a12f9c 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -25,8 +25,9 @@ namespace librealsense class firmware_logger_device : public virtual device, public firmware_logger_extensions { public: - firmware_logger_device(std::shared_ptr hardware_monitor, - const command& _fw_logs_command, const command& _flash_logs_command); + firmware_logger_device(std::shared_ptr ctx, const platform::backend_device_group group, + std::shared_ptr hardware_monitor, + const command& fw_logs_command, const command& flash_logs_command); bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; diff --git a/src/ivcam/sr300.cpp b/src/ivcam/sr300.cpp index e903b7bce1..867174bbf3 100644 --- a/src/ivcam/sr300.cpp +++ b/src/ivcam/sr300.cpp @@ -422,7 +422,7 @@ namespace librealsense const platform::backend_device_group& group, bool register_device_notifications) : device(ctx, group, register_device_notifications), - firmware_logger_device(_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()), + firmware_logger_device(ctx, group, _hw_monitor, get_firmware_logs_command(), get_flash_logs_command()), _depth_device_idx(add_sensor(create_depth_device(ctx, depth))), _depth_stream(new stream(RS2_STREAM_DEPTH)), _ir_stream(new stream(RS2_STREAM_INFRARED)), diff --git a/src/l500/l500-factory.cpp b/src/l500/l500-factory.cpp index 7bf33bd82e..c1ae01a722 100644 --- a/src/l500/l500-factory.cpp +++ b/src/l500/l500-factory.cpp @@ -42,7 +42,7 @@ namespace librealsense l500_color(ctx, group), l500_motion(ctx, group), l500_serializable(l500_device::_hw_monitor, get_depth_sensor()), - firmware_logger_device(l500_device::_hw_monitor, + firmware_logger_device(ctx, group, l500_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} @@ -74,7 +74,7 @@ namespace librealsense : device(ctx, group, register_device_notifications), l500_device(ctx, group), l500_depth(ctx, group), - firmware_logger_device(l500_device::_hw_monitor, + firmware_logger_device(ctx, group,l500_device::_hw_monitor, get_firmware_logs_command(), get_flash_logs_command()) {} From 7b08009303ce385922e56629e882fe5220444bf5 Mon Sep 17 00:00:00 2001 From: remibettan Date: Mon, 22 Jun 2020 11:49:55 +0300 Subject: [PATCH 40/43] tabs to spaces --- include/librealsense2/h/rs_internal.h | 64 +++++++++++++-------------- src/firmware_logger_device.cpp | 4 +- src/firmware_logger_device.h | 64 +++++++++++++-------------- 3 files changed, 66 insertions(+), 66 deletions(-) diff --git a/include/librealsense2/h/rs_internal.h b/include/librealsense2/h/rs_internal.h index b5150507b7..5691c63727 100644 --- a/include/librealsense2/h/rs_internal.h +++ b/include/librealsense2/h/rs_internal.h @@ -350,7 +350,7 @@ void rs2_software_sensor_detach(rs2_sensor* sensor, rs2_error** error); /** * \brief Creates RealSense firmware log message. -* \param[in] dev Device from which the FW log will be taken using the created message +* \param[in] dev Device from which the FW log will be taken using the created message * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return pointer to created empty firmware log message */ @@ -358,8 +358,8 @@ rs2_firmware_log_message* rs2_create_fw_log_message(rs2_device* dev, rs2_error** /** * \brief Gets RealSense firmware log. -* \param[in] dev Device from which the FW log should be taken -* \param[in] fw_log_msg Firmware log message object to be filled +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor */ @@ -367,8 +367,8 @@ int rs2_get_fw_log(rs2_device* dev, rs2_firmware_log_message** fw_log_msg, rs2_e /** * \brief Gets RealSense flash log - this is a fw log that has been written in the device during the previous shutdown of the device -* \param[in] dev Device from which the FW log should be taken -* \param[in] fw_log_msg Firmware log message object to be filled +* \param[in] dev Device from which the FW log should be taken +* \param[in] fw_log_msg Firmware log message object to be filled * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return true for success, false for failure - failure happens if no firmware log was sent by the hardware monitor */ @@ -382,7 +382,7 @@ void rs2_delete_fw_log_message(rs2_firmware_log_message* msg); /** * \brief Gets RealSense firmware log message data. -* \param[in] msg firmware log message object +* \param[in] msg firmware log message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return pointer to start of the firmware log message data */ @@ -390,7 +390,7 @@ const unsigned char* rs2_fw_log_message_data(rs2_firmware_log_message* msg, rs2_ /** * \brief Gets RealSense firmware log message size. -* \param[in] msg firmware log message object +* \param[in] msg firmware log message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return size of the firmware log message data */ @@ -399,7 +399,7 @@ int rs2_fw_log_message_size(rs2_firmware_log_message* msg, rs2_error** error); /** * \brief Gets RealSense firmware log message timestamp. -* \param[in] msg firmware log message object +* \param[in] msg firmware log message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return timestamp of the firmware log message */ @@ -407,7 +407,7 @@ unsigned int rs2_fw_log_message_timestamp(rs2_firmware_log_message* msg, rs2_err /** * \brief Gets RealSense firmware log message severity. -* \param[in] msg firmware log message object +* \param[in] msg firmware log message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return severity of the firmware log message data */ @@ -415,8 +415,8 @@ rs2_log_severity rs2_fw_log_message_severity(const rs2_firmware_log_message* msg /** * \brief Initializes RealSense firmware logs parser in device. -* \param[in] dev Device from which the FW log will be taken -* \param[in] xml_content content of the xml file needed for parsing +* \param[in] dev Device from which the FW log will be taken +* \param[in] xml_content content of the xml file needed for parsing * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return true for success, false for failure - failure happens if opening the xml from the xml_path input fails */ @@ -425,7 +425,7 @@ int rs2_init_fw_log_parser(rs2_device* dev, const char* xml_content, rs2_error** /** * \brief Creates RealSense firmware log parsed message. -* \param[in] dev Device from which the FW log will be taken using the created message +* \param[in] dev Device from which the FW log will be taken using the created message * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return pointer to created empty firmware log message */ @@ -433,16 +433,16 @@ rs2_firmware_log_parsed_message* rs2_create_fw_log_parsed_message(rs2_device* de /** * \brief Deletes RealSense firmware log parsed message. -* \param[in] msg message to be deleted +* \param[in] msg message to be deleted */ void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_parsed_msg); /** * \brief Gets RealSense firmware log parser -* \param[in] dev Device from which the FW log will be taken -* \param[in] fw_log_msg firmware log message to be parsed -* \param[in] parsed_msg firmware log parsed message - place holder for the resulting parsed message +* \param[in] dev Device from which the FW log will be taken +* \param[in] fw_log_msg firmware log message to be parsed +* \param[in] parsed_msg firmware log parsed message - place holder for the resulting parsed message * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return true for success, false for failure - failure happens if message could not be parsed */ @@ -456,7 +456,7 @@ void rs2_delete_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_log_pa /** * \brief Gets RealSense firmware log parsed message. -* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[in] fw_log_parsed_msg firmware log parsed message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return message of the firmware log parsed message */ @@ -464,7 +464,7 @@ const char* rs2_get_fw_log_parsed_message(rs2_firmware_log_parsed_message* fw_lo /** * \brief Gets RealSense firmware log parsed message file name. -* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[in] fw_log_parsed_msg firmware log parsed message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return file name of the firmware log parsed message */ @@ -472,7 +472,7 @@ const char* rs2_get_fw_log_parsed_file_name(rs2_firmware_log_parsed_message* fw_ /** * \brief Gets RealSense firmware log parsed message thread name. -* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[in] fw_log_parsed_msg firmware log parsed message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return thread name of the firmware log parsed message */ @@ -480,7 +480,7 @@ const char* rs2_get_fw_log_parsed_thread_name(rs2_firmware_log_parsed_message* f /** * \brief Gets RealSense firmware log parsed message severity. -* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[in] fw_log_parsed_msg firmware log parsed message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return severity of the firmware log parsed message */ @@ -488,7 +488,7 @@ rs2_log_severity rs2_get_fw_log_parsed_severity(rs2_firmware_log_parsed_message* /** * \brief Gets RealSense firmware log parsed message relevant line (in the file that is returned by rs2_get_fw_log_parsed_file_name). -* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[in] fw_log_parsed_msg firmware log parsed message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return line number of the firmware log parsed message */ @@ -496,7 +496,7 @@ unsigned int rs2_get_fw_log_parsed_line(rs2_firmware_log_parsed_message* fw_log_ /** * \brief Gets RealSense firmware log parsed message timestamp -* \param[in] fw_log_parsed_msg firmware log parsed message object +* \param[in] fw_log_parsed_msg firmware log parsed message object * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return timestamp of the firmware log parsed message */ @@ -504,7 +504,7 @@ unsigned int rs2_get_fw_log_parsed_timestamp(rs2_firmware_log_parsed_message* fw /** * \brief Creates RealSense terminal parser. -* \param[in] xml_content content of the xml file needed for parsing +* \param[in] xml_content content of the xml file needed for parsing * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return pointer to created terminal parser object */ @@ -512,15 +512,15 @@ rs2_terminal_parser* rs2_create_terminal_parser(const char* xml_content, rs2_err /** * \brief Deletes RealSense terminal parser. -* \param[in] terminal_parser terminal parser to be deleted +* \param[in] terminal_parser terminal parser to be deleted */ void rs2_delete_terminal_parser(rs2_terminal_parser* terminal_parser); /** * \brief Parses terminal command via RealSense terminal parser -* \param[in] terminal_parser Terminal parser object -* \param[in] command command to be sent to the hw monitor of the device -* \param[in] size_of_command size of command to be sent to the hw monitor of the device +* \param[in] terminal_parser Terminal parser object +* \param[in] command command to be sent to the hw monitor of the device +* \param[in] size_of_command size of command to be sent to the hw monitor of the device * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return command to hw monitor, in hex */ @@ -529,11 +529,11 @@ rs2_raw_data_buffer* rs2_terminal_parse_command(rs2_terminal_parser* terminal_pa /** * \brief Parses terminal response via RealSense terminal parser -* \param[in] terminal_parser Terminal parser object -* \param[in] command command sent to the hw monitor of the device -* \param[in] size_of_command size of the command to sent to the hw monitor of the device -* \param[in] response response received by the hw monitor of the device -* \param[in] size_of_response size of the response received by the hw monitor of the device +* \param[in] terminal_parser Terminal parser object +* \param[in] command command sent to the hw monitor of the device +* \param[in] size_of_command size of the command to sent to the hw monitor of the device +* \param[in] response response received by the hw monitor of the device +* \param[in] size_of_response size of the response received by the hw monitor of the device * \param[out] error If non-null, receives any error that occurs during this call, otherwise, errors are ignored. * \return answer parsed */ diff --git a/src/firmware_logger_device.cpp b/src/firmware_logger_device.cpp index 647c699c67..63564c52cd 100644 --- a/src/firmware_logger_device.cpp +++ b/src/firmware_logger_device.cpp @@ -119,7 +119,7 @@ namespace librealsense bool firmware_logger_device::parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) - { + { bool result = false; if (_parser && parsed_msg && fw_log_msg) { @@ -128,6 +128,6 @@ namespace librealsense } return result; - } + } } diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 7634a12f9c..2eb6ae1ac1 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -11,48 +11,48 @@ namespace librealsense { - class firmware_logger_extensions - { - public: - virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; - virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; - virtual bool init_parser(std::string xml_content) = 0; - virtual bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) = 0; - virtual ~firmware_logger_extensions() = default; - }; - MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); + class firmware_logger_extensions + { + public: + virtual bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) = 0; + virtual bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) = 0; + virtual bool init_parser(std::string xml_content) = 0; + virtual bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) = 0; + virtual ~firmware_logger_extensions() = default; + }; + MAP_EXTENSION(RS2_EXTENSION_FW_LOGGER, librealsense::firmware_logger_extensions); - class firmware_logger_device : public virtual device, public firmware_logger_extensions - { - public: - firmware_logger_device(std::shared_ptr ctx, const platform::backend_device_group group, - std::shared_ptr hardware_monitor, - const command& fw_logs_command, const command& flash_logs_command); + class firmware_logger_device : public virtual device, public firmware_logger_extensions + { + public: + firmware_logger_device(std::shared_ptr ctx, const platform::backend_device_group group, + std::shared_ptr hardware_monitor, + const command& fw_logs_command, const command& flash_logs_command); - bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; - bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; + bool get_fw_log(fw_logs::fw_logs_binary_data& binary_data) override; + bool get_flash_log(fw_logs::fw_logs_binary_data& binary_data) override; - bool init_parser(std::string xml_content) override; - bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; + bool init_parser(std::string xml_content) override; + bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; - private: + private: - void get_fw_logs_from_hw_monitor(); - void get_flash_logs_from_hw_monitor(); + void get_fw_logs_from_hw_monitor(); + void get_flash_logs_from_hw_monitor(); - command _fw_logs_command; - command _flash_logs_command; + command _fw_logs_command; + command _flash_logs_command; - std::shared_ptr _hw_monitor; + std::shared_ptr _hw_monitor; - std::queue _fw_logs; - std::queue _flash_logs; + std::queue _fw_logs; + std::queue _flash_logs; - bool _flash_logs_initialized; + bool _flash_logs_initialized; - fw_logs::fw_logs_parser* _parser; - uint16_t _device_pid; + fw_logs::fw_logs_parser* _parser; + uint16_t _device_pid; - }; + }; } From 408f2e10989c48ff259f25752166d5bcd8d67b1e Mon Sep 17 00:00:00 2001 From: remibettan Date: Mon, 22 Jun 2020 12:28:29 +0300 Subject: [PATCH 41/43] correct stoi call for linux build --- src/fw-logs/fw-logs-xml-helper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/fw-logs/fw-logs-xml-helper.cpp b/src/fw-logs/fw-logs-xml-helper.cpp index 42adfd501d..e5f19f1b37 100644 --- a/src/fw-logs/fw-logs-xml-helper.cpp +++ b/src/fw-logs/fw-logs-xml-helper.cpp @@ -145,7 +145,7 @@ namespace librealsense try { auto key_str = std::string(attribute->value()); - key = std::stoi(key_str, nullptr); + key = std::stoi(key_str); } catch (...) {} } From 428130708d141aac8e49d1f82a5a719883743c30 Mon Sep 17 00:00:00 2001 From: ev-mp Date: Mon, 22 Jun 2020 23:27:59 +0300 Subject: [PATCH 42/43] relax unit-tests criteria for specific pipeline cases --- unit-tests/unit-tests-live.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/unit-tests/unit-tests-live.cpp b/unit-tests/unit-tests-live.cpp index fbf811d847..8ba70c49f0 100644 --- a/unit-tests/unit-tests-live.cpp +++ b/unit-tests/unit-tests-live.cpp @@ -2980,7 +2980,7 @@ static const std::map< dev_type, device_profiles> pipeline_default_configuration /* SR300*/ { { "0AA5", true } ,{ { { RS2_STREAM_DEPTH, RS2_FORMAT_Z16, 640, 480, 0 },{ RS2_STREAM_COLOR, RS2_FORMAT_RGB8, 1920, 1080, 0 } }, 30, true } }, }; -TEST_CASE("Pipeline wait_for_frames", "[live][pipeline][using_pipeline]") { +TEST_CASE("Pipeline wait_for_frames", "[live][pipeline][using_pipeline][!mayfail]") { rs2::context ctx; @@ -3046,7 +3046,7 @@ TEST_CASE("Pipeline wait_for_frames", "[live][pipeline][using_pipeline]") { } } -TEST_CASE("Pipeline poll_for_frames", "[live][pipeline][using_pipeline]") +TEST_CASE("Pipeline poll_for_frames", "[live][pipeline][using_pipeline][!mayfail]") { rs2::context ctx; @@ -3311,7 +3311,7 @@ TEST_CASE("Pipeline enable stream auto complete", "[live][pipeline][using_pipeli } } -TEST_CASE("Pipeline disable_all", "[live][pipeline][using_pipeline]") { +TEST_CASE("Pipeline disable_all", "[live][pipeline][using_pipeline][!mayfail]") { auto not_default_configurations = pipeline_custom_configurations; auto default_configurations = pipeline_default_configurations; @@ -4730,7 +4730,7 @@ TEST_CASE("Pipeline stream enable hierarchy", "[pipeline]") } } -TEST_CASE("Pipeline stream with callback", "[live][pipeline][using_pipeline]") +TEST_CASE("Pipeline stream with callback", "[live][pipeline][using_pipeline][!mayfail]") { rs2::context ctx; @@ -5830,7 +5830,7 @@ TEST_CASE("Wheel_Odometry_API", "[live]") } -TEST_CASE("get_sensor_from_frame", "[live][using_pipeline]") +TEST_CASE("get_sensor_from_frame", "[live][using_pipeline][!mayfail]") { // Require at least one device to be plugged in rs2::context ctx; From 5c275658643b5d1391fecfa05c91e31526bee5aa Mon Sep 17 00:00:00 2001 From: Evgeni Raikhel Date: Tue, 23 Jun 2020 12:29:52 +0300 Subject: [PATCH 43/43] Temporal work-around for HW Monitor injection for SR300 Change-Id: I427e31accda8f88bd17b0da5fbd130998dce8133 --- src/firmware_logger_device.h | 4 ++++ src/ivcam/sr300.cpp | 6 ++++-- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/firmware_logger_device.h b/src/firmware_logger_device.h index 2eb6ae1ac1..2d948b3f36 100644 --- a/src/firmware_logger_device.h +++ b/src/firmware_logger_device.h @@ -35,6 +35,10 @@ namespace librealsense bool init_parser(std::string xml_content) override; bool parse_log(const fw_logs::fw_logs_binary_data* fw_log_msg, fw_logs::fw_log_data* parsed_msg) override; + // Temporal solution for HW_Monitor injection + void assign_hw_monitor(std::shared_ptr hardware_monitor) + { _hw_monitor = hardware_monitor; } + private: void get_fw_logs_from_hw_monitor(); diff --git a/src/ivcam/sr300.cpp b/src/ivcam/sr300.cpp index 867174bbf3..ebbb564fd8 100644 --- a/src/ivcam/sr300.cpp +++ b/src/ivcam/sr300.cpp @@ -381,7 +381,7 @@ namespace librealsense return flash; } - void sr300_camera::update_flash(const std::vector& image, update_progress_callback_ptr callback, int update_mode) + void sr300_camera::update_flash(const std::vector&, update_progress_callback_ptr, int) { throw std::runtime_error("update_flash is not supported by SR300"); } @@ -422,7 +422,7 @@ namespace librealsense const platform::backend_device_group& group, bool register_device_notifications) : device(ctx, group, register_device_notifications), - firmware_logger_device(ctx, group, _hw_monitor, get_firmware_logs_command(), get_flash_logs_command()), + firmware_logger_device(ctx, group, nullptr, get_firmware_logs_command(), get_flash_logs_command()), _depth_device_idx(add_sensor(create_depth_device(ctx, depth))), _depth_stream(new stream(RS2_STREAM_DEPTH)), _ir_stream(new stream(RS2_STREAM_INFRARED)), @@ -433,6 +433,8 @@ namespace librealsense using namespace ivcam; static auto device_name = "Intel RealSense SR300"; + // Temporal solution for HW Monitor injection - to be refactored + this->assign_hw_monitor(_hw_monitor); std::vector gvd_buff(HW_MONITOR_BUFFER_SIZE); _hw_monitor->get_gvd(gvd_buff.size(), gvd_buff.data(), GVD); // fooling tests recordings - don't remove