Skip to content

Commit

Permalink
PR IntelRealSense#12372 from Eran: clean up types.h
Browse files Browse the repository at this point in the history
  • Loading branch information
maloel authored Nov 7, 2023
2 parents ceb205f + 43858bd commit 5026b67
Show file tree
Hide file tree
Showing 126 changed files with 987 additions and 1,289 deletions.
65 changes: 3 additions & 62 deletions common/calibration-model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,8 @@ bool calibration_model::supports()

void calibration_model::draw_float(std::string name, float& x, const float& orig, bool& changed)
{
if (abs(x - orig) > 0.00001) ImGui::PushStyleColor(ImGuiCol_FrameBg, regular_blue);
if( std::abs( x - orig ) > 0.00001 )
ImGui::PushStyleColor( ImGuiCol_FrameBg, regular_blue );
else ImGui::PushStyleColor(ImGuiCol_FrameBg, black);
if (ImGui::DragFloat(std::string( rsutils::string::from() << "##" << name).c_str(), &x, 0.001f))
{
Expand Down Expand Up @@ -71,66 +72,6 @@ void calibration_model::draw_float4x4(std::string name, librealsense::float3x3&
ImGui::SetCursorPosY(ImGui::GetCursorPosY() + 5);
}

namespace helpers
{
#define UPDC32(octet, crc) (crc_32_tab[((crc) ^ (octet)) & 0xff] ^ ((crc) >> 8))

static const uint32_t crc_32_tab[] = { /* CRC polynomial 0xedb88320 */
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f,
0xe963a535, 0x9e6495a3, 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988,
0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, 0x1db71064, 0x6ab020f2,
0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9,
0xfa0f3d63, 0x8d080df5, 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172,
0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, 0x35b5a8fa, 0x42b2986c,
0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423,
0xcfba9599, 0xb8bda50f, 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924,
0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, 0x76dc4190, 0x01db7106,
0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d,
0x91646c97, 0xe6635c01, 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e,
0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, 0x65b0d9c6, 0x12b7e950,
0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7,
0xa4d1c46d, 0xd3d6f4fb, 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0,
0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, 0x5005713c, 0x270241aa,
0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81,
0xb7bd5c3b, 0xc0ba6cad, 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a,
0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, 0xe3630b12, 0x94643b84,
0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb,
0x196c3671, 0x6e6b06e7, 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc,
0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, 0xd6d6a3e8, 0xa1d1937e,
0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55,
0x316e8eef, 0x4669be79, 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236,
0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, 0xc5ba3bbe, 0xb2bd0b28,
0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f,
0x72076785, 0x05005713, 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38,
0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, 0x86d3d2d4, 0xf1d4e242,
0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69,
0x616bffd3, 0x166ccf45, 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2,
0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, 0xaed16a4a, 0xd9d65adc,
0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693,
0x54de5729, 0x23d967bf, 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94,
0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
};

/// Calculate CRC code for arbitrary characters buffer
uint32_t calc_crc32(const uint8_t *buf, size_t bufsize)
{
uint32_t oldcrc32 = 0xFFFFFFFF;
for (; bufsize; --bufsize, ++buf)
oldcrc32 = UPDC32(*buf, oldcrc32);
return ~oldcrc32;
}
}

void calibration_model::update(ux_window& window, std::string& error_message)
{
const auto window_name = "Calibration Window";
Expand Down Expand Up @@ -445,7 +386,7 @@ void calibration_model::update(ux_window& window, std::string& error_message)
{
auto actual_data = _calibration.data() + sizeof(librealsense::ds::table_header);
auto actual_data_size = _calibration.size() - sizeof(librealsense::ds::table_header);
auto crc = helpers::calc_crc32(actual_data, actual_data_size);
auto crc = rsutils::number::calc_crc32( actual_data, actual_data_size );
table->header.crc32 = crc;
dev.as<rs2::auto_calibrated_device>().set_calibration_table(_calibration);
dev.as<rs2::auto_calibrated_device>().write_calibration();
Expand Down
6 changes: 0 additions & 6 deletions common/calibration-model.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,6 @@ namespace librealsense
struct float3x3;
}

namespace helpers
{
// Calculate CRC code for arbitrary characters buffer
uint32_t calc_crc32(const uint8_t* buf, size_t bufsize);
}

namespace rs2
{
class ux_window;
Expand Down
1 change: 1 addition & 0 deletions common/fw-update-helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@

#include "os.h"

#include <rsutils/easylogging/easyloggingpp.h>
#include <map>
#include <vector>
#include <string>
Expand Down
2 changes: 1 addition & 1 deletion common/measurement.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ float measurement::calculate_area(std::vector<float3> poly)
auto a = poly[1] - poly[0];
auto b = poly[2] - poly[0];
auto n = cross(a, b);
return abs(total * n.normalize()) / 2;
return std::abs( total * n.normalize() ) / 2;
}

void draw_sphere(const float3& pos, float r, int lats, int longs)
Expand Down
2 changes: 1 addition & 1 deletion common/os.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,7 @@ Some auxillary functionalities might be affected. Please report this message if
if (filters_split.size() >= 1)
{
filters_count = filters_split.size() - 1;
filters_count = int( filters_split.size() - 1 );
// set description
aSingleFilterDescription = filters_split[0].c_str();
Expand Down
1 change: 1 addition & 0 deletions common/post-processing-filter.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <librealsense2/rs.hpp>
#include <model-views.h>
#include <viewer.h>
#include <rsutils/easylogging/easyloggingpp.h>


/*
Expand Down
1 change: 0 additions & 1 deletion common/realsense-ui-advanced-mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@
#pragma once

#include <librealsense2/rs_advanced_mode.hpp>
#include <types.h>
#include <type_traits>
#include <rsutils/string/string-utilities.h>

Expand Down
8 changes: 6 additions & 2 deletions common/reflectivity/reflectivity.cpp
Original file line number Diff line number Diff line change
@@ -1,9 +1,13 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#include <numeric>
#include "reflectivity.h"
#include <types.h>
#include <vector>
#include <numeric>
#include <algorithm>
#include <stdexcept>
#include <cmath>
#include <limits>

using namespace rs2;

Expand Down
3 changes: 2 additions & 1 deletion common/sw-update/http-downloader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,13 @@
#include <thread>
#include <atomic>
#include <mutex>
#include <fstream>
#include <curl/curl.h>
#include <curl/easy.h>
#include "types.h"
#endif // CHECK_FOR_UPDATES

#include "http-downloader.h"
#include <rsutils/easylogging/easyloggingpp.h>


namespace rs2
Expand Down
9 changes: 5 additions & 4 deletions common/sw-update/versions-db-manager.cpp
Original file line number Diff line number Diff line change
@@ -1,14 +1,15 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2020 Intel Corporation. All Rights Reserved.

#include "versions-db-manager.h"
#include <nlohmann/json.hpp>
#include <rsutils/os/os.h>
#include <rsutils/easylogging/easyloggingpp.h>
#include <fstream>
#include <unordered_map>
#include <algorithm>
#include <regex>

#include <nlohmann/json.hpp>
#include "versions-db-manager.h"
#include <types.h>
#include <rsutils/os/os.h>

namespace rs2
{
Expand Down
1 change: 1 addition & 0 deletions common/updates-model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include "os.h"
#include <stb_image.h>
#include "sw-update/http-downloader.h"
#include <rsutils/easylogging/easyloggingpp.h>

using namespace rs2;
using namespace sw_update;
Expand Down
9 changes: 9 additions & 0 deletions include/librealsense2/hpp/rs_types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,20 +28,23 @@ struct rs2_frame_callback
virtual void release() = 0;
virtual ~rs2_frame_callback() {}
};
typedef std::shared_ptr<rs2_frame_callback> rs2_frame_callback_sptr;

struct rs2_frame_processor_callback
{
virtual void on_frame(rs2_frame * f, rs2_source * source) = 0;
virtual void release() = 0;
virtual ~rs2_frame_processor_callback() {}
};
typedef std::shared_ptr<rs2_frame_processor_callback> rs2_frame_processor_callback_sptr;

struct rs2_notifications_callback
{
virtual void on_notification(rs2_notification* n) = 0;
virtual void release() = 0;
virtual ~rs2_notifications_callback() {}
};
typedef std::shared_ptr<rs2_notifications_callback> rs2_notifications_callback_sptr;

typedef void ( *log_callback_function_ptr )(rs2_log_severity severity, rs2_log_message const * msg );

Expand All @@ -51,41 +54,47 @@ struct rs2_software_device_destruction_callback
virtual void release() = 0;
virtual ~rs2_software_device_destruction_callback() {}
};
typedef std::shared_ptr<rs2_software_device_destruction_callback> rs2_software_device_destruction_callback_sptr;

struct rs2_log_callback
{
virtual void on_log( rs2_log_severity severity, rs2_log_message const & msg ) noexcept = 0;
virtual void release() = 0;
virtual ~rs2_log_callback() {}
};
typedef std::shared_ptr< rs2_log_callback > rs2_log_callback_sptr;

struct rs2_calibration_change_callback
{
virtual void on_calibration_change( rs2_calibration_status ) noexcept = 0;
virtual void release() = 0;
virtual ~rs2_calibration_change_callback() {}
};
typedef std::shared_ptr<rs2_calibration_change_callback> rs2_calibration_change_callback_sptr;

struct rs2_devices_changed_callback
{
virtual void on_devices_changed(rs2_device_list* removed, rs2_device_list* added) = 0;
virtual void release() = 0;
virtual ~rs2_devices_changed_callback() {}
};
typedef std::shared_ptr<rs2_devices_changed_callback> rs2_devices_changed_callback_sptr;

struct rs2_playback_status_changed_callback
{
virtual void on_playback_status_changed(rs2_playback_status status) = 0;
virtual void release() = 0;
virtual ~rs2_playback_status_changed_callback() {}
};
typedef std::shared_ptr<rs2_playback_status_changed_callback> rs2_playback_status_changed_callback_sptr;

struct rs2_update_progress_callback
{
virtual void on_update_progress(const float update_progress) = 0;
virtual void release() = 0;
virtual ~rs2_update_progress_callback() {}
};
typedef std::shared_ptr<rs2_update_progress_callback> rs2_update_progress_callback_sptr;

namespace rs2
{
Expand Down
3 changes: 3 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -111,6 +111,7 @@ target_sources(${LRS_TARGET}
"${CMAKE_CURRENT_LIST_DIR}/platform/platform-device-info.h"
"${CMAKE_CURRENT_LIST_DIR}/platform/device-watcher.h"
"${CMAKE_CURRENT_LIST_DIR}/platform/frame-object.h"
"${CMAKE_CURRENT_LIST_DIR}/platform/hid-data.h"
"${CMAKE_CURRENT_LIST_DIR}/platform/hid-device.h"
"${CMAKE_CURRENT_LIST_DIR}/platform/hid-device-info.h"
"${CMAKE_CURRENT_LIST_DIR}/platform/playback-device-info.h"
Expand All @@ -127,6 +128,8 @@ target_sources(${LRS_TARGET}
"${CMAKE_CURRENT_LIST_DIR}/device-info.h"
"${CMAKE_CURRENT_LIST_DIR}/device_hub.h"
"${CMAKE_CURRENT_LIST_DIR}/environment.h"
"${CMAKE_CURRENT_LIST_DIR}/firmware-version.h"
"${CMAKE_CURRENT_LIST_DIR}/fourcc.h"
"${CMAKE_CURRENT_LIST_DIR}/log.h"
"${CMAKE_CURRENT_LIST_DIR}/error-handling.h"
"${CMAKE_CURRENT_LIST_DIR}/firmware_logger_device.h"
Expand Down
8 changes: 4 additions & 4 deletions src/algo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -893,10 +893,10 @@ bool rect_gaussian_dots_target_calculator::validate_corners(const uint8_t* img)
bool ok = true;

static const int pos_diff_threshold = 4;
if (abs(_corners[0].x - _corners[2].x) > pos_diff_threshold ||
abs(_corners[1].x - _corners[3].x) > pos_diff_threshold ||
abs(_corners[0].y - _corners[1].y) > pos_diff_threshold ||
abs(_corners[2].y - _corners[3].y) > pos_diff_threshold)
if( std::abs( _corners[0].x - _corners[2].x ) > pos_diff_threshold
|| std::abs( _corners[1].x - _corners[3].x ) > pos_diff_threshold
|| std::abs( _corners[0].y - _corners[1].y ) > pos_diff_threshold
|| std::abs( _corners[2].y - _corners[3].y ) > pos_diff_threshold )
{
ok = false;
}
Expand Down
12 changes: 6 additions & 6 deletions src/auto-calibrated-device.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,18 +13,18 @@ namespace librealsense
{
public:
virtual void write_calibration() const = 0;
virtual std::vector<uint8_t> run_on_chip_calibration(int timeout_ms, std::string json, float* const health, update_progress_callback_ptr progress_callback) = 0;
virtual std::vector<uint8_t> run_tare_calibration( int timeout_ms, float ground_truth_mm, std::string json, float* const health, update_progress_callback_ptr progress_callback) = 0;
virtual std::vector<uint8_t> process_calibration_frame(int timeout_ms, const rs2_frame* f, float* const health, update_progress_callback_ptr progress_callback) = 0;
virtual std::vector<uint8_t> run_on_chip_calibration(int timeout_ms, std::string json, float* const health, rs2_update_progress_callback_sptr progress_callback) = 0;
virtual std::vector<uint8_t> run_tare_calibration( int timeout_ms, float ground_truth_mm, std::string json, float* const health, rs2_update_progress_callback_sptr progress_callback) = 0;
virtual std::vector<uint8_t> process_calibration_frame(int timeout_ms, const rs2_frame* f, float* const health, rs2_update_progress_callback_sptr progress_callback) = 0;
virtual std::vector<uint8_t> get_calibration_table() const = 0;
virtual void set_calibration_table(const std::vector<uint8_t>& calibration) = 0;
virtual void reset_to_factory_calibration() const = 0;
virtual std::vector<uint8_t> run_focal_length_calibration(rs2_frame_queue* left, rs2_frame_queue* right, float target_w, float target_h,
int adjust_both_sides, float* ratio, float* angle, update_progress_callback_ptr progress_callback) = 0;
int adjust_both_sides, float* ratio, float* angle, rs2_update_progress_callback_sptr progress_callback) = 0;
virtual std::vector<uint8_t> run_uv_map_calibration(rs2_frame_queue* left, rs2_frame_queue* color, rs2_frame_queue* depth, int py_px_only,
float* const health, int health_size, update_progress_callback_ptr progress_callback) = 0;
float* const health, int health_size, rs2_update_progress_callback_sptr progress_callback) = 0;
virtual float calculate_target_z(rs2_frame_queue* queue1, rs2_frame_queue* queue2, rs2_frame_queue* queue3,
float target_w, float target_h, update_progress_callback_ptr progress_callback) = 0;
float target_w, float target_h, rs2_update_progress_callback_sptr progress_callback) = 0;
};
MAP_EXTENSION(RS2_EXTENSION_AUTO_CALIBRATED_DEVICE, auto_calibrated_interface);
}
2 changes: 2 additions & 0 deletions src/core/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ target_sources(${LRS_TARGET}
"${CMAKE_CURRENT_LIST_DIR}/disparity-frame.h"
"${CMAKE_CURRENT_LIST_DIR}/frame-continuation.h"
"${CMAKE_CURRENT_LIST_DIR}/frame-additional-data.h"
"${CMAKE_CURRENT_LIST_DIR}/frame-callback.h"
"${CMAKE_CURRENT_LIST_DIR}/frame-header.h"
"${CMAKE_CURRENT_LIST_DIR}/frame-holder.h"
"${CMAKE_CURRENT_LIST_DIR}/frame-interface.h"
Expand All @@ -20,6 +21,7 @@ target_sources(${LRS_TARGET}
"${CMAKE_CURRENT_LIST_DIR}/motion.h"
"${CMAKE_CURRENT_LIST_DIR}/motion-frame.h"
"${CMAKE_CURRENT_LIST_DIR}/notification.h"
"${CMAKE_CURRENT_LIST_DIR}/notification.cpp"
"${CMAKE_CURRENT_LIST_DIR}/video.h"
"${CMAKE_CURRENT_LIST_DIR}/video-frame.h"
"${CMAKE_CURRENT_LIST_DIR}/options-container.h"
Expand Down
41 changes: 41 additions & 0 deletions src/core/frame-callback.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
// License: Apache 2.0. See LICENSE file in root directory.
// Copyright(c) 2023 Intel Corporation. All Rights Reserved.
#pragma once

#include <librealsense2/hpp/rs_types.hpp>
#include <memory>
#include <functional>


namespace librealsense {


class frame_interface;


struct frame_callback : public rs2_frame_callback
{
using fn = std::function< void( frame_interface * ) >;

explicit frame_callback( fn && on_frame )
: _on_frame( std::move( on_frame ) )
{
}

void on_frame( rs2_frame * fref ) override { _on_frame( (frame_interface *)( fref ) ); }

void release() override { delete this; }

private:
fn _on_frame;
};


inline rs2_frame_callback_sptr make_frame_callback( std::function< void( frame_interface * ) > && callback )
{
return { new frame_callback( std::move( callback ) ),
[]( rs2_frame_callback * p ) { p->release(); } };
}


} // namespace librealsense
Loading

0 comments on commit 5026b67

Please sign in to comment.