Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Move stuff to and from common DS #11479

Merged
merged 2 commits into from
Feb 26, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 10 additions & 10 deletions common/calibration-model.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,8 +146,8 @@ void calibration_model::update(ux_window& window, std::string& error_message)
to_open = false;
}

auto table = (librealsense::ds::coefficients_table*)_calibration.data();
auto orig_table = (librealsense::ds::coefficients_table*)_original.data();
auto table = (librealsense::ds::d400_coefficients_table*)_calibration.data();
auto orig_table = (librealsense::ds::d400_coefficients_table*)_original.data();
bool changed = false;

const float w = 620;
Expand Down Expand Up @@ -210,7 +210,7 @@ void calibration_model::update(ux_window& window, std::string& error_message)
load_float3x4("world2left_rot", table->world2left_rot);
load_float3x4("world2right_rot", table->world2right_rot);

for (int i = 0; i < librealsense::ds::max_d400_rect_resolutions; i++)
for (int i = 0; i < librealsense::ds::max_ds_rect_resolutions; i++)
{
table->rect_params[i].x = cf.get(std::string( rsutils::string::from() << "rectified." << i << ".fx").c_str());
table->rect_params[i].y = cf.get(std::string( rsutils::string::from() << "rectified." << i << ".fy").c_str());
Expand Down Expand Up @@ -262,9 +262,9 @@ void calibration_model::update(ux_window& window, std::string& error_message)
save_float3x4("world2left_rot", table->world2left_rot);
save_float3x4("world2right_rot", table->world2right_rot);

for (int i = 0; i < librealsense::ds::max_d400_rect_resolutions; i++)
for (int i = 0; i < librealsense::ds::max_ds_rect_resolutions; i++)
{
auto xy = librealsense::ds::resolutions_list[(librealsense::ds::d400_rect_resolutions)i];
auto xy = librealsense::ds::resolutions_list[(librealsense::ds::ds_rect_resolutions)i];
int w = xy.x; int h = xy.y;

cf.set(std::string( rsutils::string::from() << "rectified." << i << ".width").c_str(), w);
Expand Down Expand Up @@ -299,8 +299,8 @@ void calibration_model::update(ux_window& window, std::string& error_message)
dev.as<rs2::auto_calibrated_device>().reset_to_factory_calibration();
_calibration = dev.as<rs2::auto_calibrated_device>().get_calibration_table();
_original = _calibration;
table = reinterpret_cast< librealsense::ds::coefficients_table * >( _calibration.data() );
orig_table = reinterpret_cast< librealsense::ds::coefficients_table * >( _original.data() );
table = reinterpret_cast< librealsense::ds::d400_coefficients_table * >( _calibration.data() );
orig_table = reinterpret_cast< librealsense::ds::d400_coefficients_table * >( _original.data() );
changed = true;

if (auto nm = _not_model.lock())
Expand Down Expand Up @@ -364,9 +364,9 @@ void calibration_model::update(ux_window& window, std::string& error_message)
std::vector<std::string> resolution_names;
std::vector<const char*> resolution_names_char;
std::vector<int> resolution_offset;
for (int i = 0; i < librealsense::ds::max_d400_rect_resolutions; i++)
for (int i = 0; i < librealsense::ds::max_ds_rect_resolutions; i++)
{
auto xy = librealsense::ds::resolutions_list[(librealsense::ds::d400_rect_resolutions)i];
auto xy = librealsense::ds::resolutions_list[(librealsense::ds::ds_rect_resolutions)i];
int w = xy.x; int h = xy.y;
if (w != 0) {
resolution_offset.push_back(i);
Expand Down Expand Up @@ -446,7 +446,7 @@ void calibration_model::update(ux_window& window, std::string& error_message)
dev.as<rs2::auto_calibrated_device>().set_calibration_table(_calibration);
dev.as<rs2::auto_calibrated_device>().write_calibration();
_original = _calibration;
orig_table = reinterpret_cast< librealsense::ds::coefficients_table * >( _original.data() );
orig_table = reinterpret_cast< librealsense::ds::d400_coefficients_table * >( _original.data() );
ImGui::CloseCurrentPopup();
}
catch (const std::exception& ex)
Expand Down
36 changes: 20 additions & 16 deletions src/ds/d400/d400-auto-calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,9 +186,8 @@ namespace librealsense
const int DEFAULT_FY_SCAN_DIRECTION = 0;
const int DEFAULT_WHITE_WALL_MODE = 0;

auto_calibrated::auto_calibrated(std::shared_ptr<hw_monitor>& hwm)
: _hw_monitor(hwm),
_interactive_state(interactive_calibration_state::RS2_OCC_STATE_NOT_ACTIVE),
auto_calibrated::auto_calibrated()
: _interactive_state(interactive_calibration_state::RS2_OCC_STATE_NOT_ACTIVE),
_interactive_scan(false),
_action(auto_calib_action::RS2_OCC_ACTION_ON_CHIP_CALIB),
_average_step_count(-1),
Expand Down Expand Up @@ -1769,7 +1768,7 @@ namespace librealsense
std::vector<uint8_t> res;

// Fetch current calibration using GETINITCAL command
command cmd(ds::GETINTCAL, ds::coefficients_table_id);
command cmd(ds::GETINTCAL, static_cast<int>(ds::d400_calibration_table_id::coefficients_table_id));
auto calib = _hw_monitor->send(cmd);

if (calib.size() < sizeof(table_header)) throw std::runtime_error("Missing calibration header from GETINITCAL!");
Expand All @@ -1793,28 +1792,28 @@ namespace librealsense
throw std::runtime_error("Write calibration can be called only after set calibration table was called");

table_header* hd = (table_header*)(_curr_calibration.data());
calibration_table_id tbl_id = static_cast<calibration_table_id>(hd->table_type);
d400_calibration_table_id tbl_id = static_cast<d400_calibration_table_id>(hd->table_type);
fw_cmd cmd{};
uint32_t param2 = 0;
switch (tbl_id)
{
case coefficients_table_id:
case d400_calibration_table_id::coefficients_table_id:
cmd = SETINTCAL;
break;
case rgb_calibration_id:
case d400_calibration_table_id::rgb_calibration_id:
cmd = SETINTCALNEW;
param2 = 1;
break;
default:
throw std::runtime_error( rsutils::string::from() << "Flashing calibration table type 0x" << std::hex
<< tbl_id << " is not supported" );
<< static_cast<int>(tbl_id) << " is not supported" );
}

command write_calib(cmd, tbl_id, param2);
command write_calib(cmd, static_cast<int>(tbl_id), param2);
write_calib.data = _curr_calibration;
_hw_monitor->send(write_calib);

LOG_DEBUG("Flashing " << ((tbl_id == coefficients_table_id) ? "Depth" : "RGB") << " calibration table");
LOG_DEBUG("Flashing " << ((tbl_id == d400_calibration_table_id::coefficients_table_id) ? "Depth" : "RGB") << " calibration table");

}

Expand All @@ -1823,11 +1822,11 @@ namespace librealsense
using namespace ds;

table_header* hd = (table_header*)(calibration.data());
ds::calibration_table_id tbl_id = static_cast<ds::calibration_table_id>(hd->table_type);
ds::d400_calibration_table_id tbl_id = static_cast<ds::d400_calibration_table_id >(hd->table_type);

switch (tbl_id)
{
case coefficients_table_id: // Load the modified depth calib table into flash RAM
case d400_calibration_table_id::coefficients_table_id: // Load the modified depth calib table into flash RAM
{
uint8_t* table = (uint8_t*)(calibration.data() + sizeof(table_header));
command write_calib(ds::CALIBRECALC, 0, 0, 0, 0xcafecafe);
Expand All @@ -1841,12 +1840,12 @@ namespace librealsense
LOG_ERROR("Flashing coefficients_table_id failed");
}
}
case rgb_calibration_id: // case fall-through by design. For RGB skip loading to RAM (not supported)
case d400_calibration_table_id::rgb_calibration_id: // case fall-through by design. For RGB skip loading to RAM (not supported)
_curr_calibration = calibration;
break;
default:
throw std::runtime_error( rsutils::string::from()
<< "the operation is not defined for calibration table type " << tbl_id );
<< "the operation is not defined for calibration table type " << static_cast<int>(tbl_id));
}
}

Expand Down Expand Up @@ -1929,7 +1928,7 @@ namespace librealsense
const float correction_factor = 0.5f;

auto calib_table = get_calibration_table();
auto table = (librealsense::ds::coefficients_table*)calib_table.data();
auto table = (librealsense::ds::d400_coefficients_table*)calib_table.data();

float ar[2] = { 0 };
float tmp = left_rect_sides[2] + left_rect_sides[3];
Expand Down Expand Up @@ -2418,7 +2417,7 @@ namespace librealsense
const float max_change = 16.0f;
if (fabs(color_intrin.ppx - ppx) < max_change && fabs(color_intrin.ppy - ppy) < max_change && fabs(color_intrin.fx - fx) < max_change && fabs(color_intrin.fy - fy) < max_change)
{
ret = _hw_monitor->send(command{ds::GETINTCAL, ds::rgb_calibration_id });
ret = _hw_monitor->send(command{ds::GETINTCAL, static_cast<int>(ds::d400_calibration_table_id::rgb_calibration_id) });
auto table = reinterpret_cast<librealsense::ds::rgb_calibration_table*>(ret.data());

health[0] = table->intrinsic(2, 0); // px
Expand Down Expand Up @@ -2548,4 +2547,9 @@ namespace librealsense
else
throw std::runtime_error("Failed to extract target dimension info!");
}

void auto_calibrated::set_hw_monitor_for_auto_calib(std::shared_ptr<hw_monitor> hwm)
{
_hw_monitor = hwm;
}
}
5 changes: 3 additions & 2 deletions src/ds/d400/d400-auto-calibration.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ namespace librealsense
};

public:
auto_calibrated(std::shared_ptr<hw_monitor>& hwm);
auto_calibrated();
void write_calibration() const override;
std::vector<uint8_t> run_on_chip_calibration(int timeout_ms, std::string json, float* const health, update_progress_callback_ptr progress_callback) override;
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) override;
Expand All @@ -60,6 +60,7 @@ namespace librealsense
float* const health, int health_size, update_progress_callback_ptr progress_callback) override;
float calculate_target_z(rs2_frame_queue* queue1, rs2_frame_queue* queue2, rs2_frame_queue* queue3,
float target_width, float target_height, update_progress_callback_ptr progress_callback) override;
void set_hw_monitor_for_auto_calib(std::shared_ptr<hw_monitor> hwm);

private:
std::vector<uint8_t> get_calibration_results(float* const health = nullptr) const;
Expand All @@ -84,7 +85,7 @@ namespace librealsense
DirectSearchCalibrationResult get_calibration_status(int timeout_ms, std::function<void(const int count)> progress_func, bool wait_for_final_results = true);

std::vector<uint8_t> _curr_calibration;
std::shared_ptr<hw_monitor>& _hw_monitor;
std::shared_ptr<hw_monitor> _hw_monitor;

bool _preset_change = false;
preset _old_preset_values;
Expand Down
8 changes: 4 additions & 4 deletions src/ds/d400/d400-color.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace librealsense

_color_calib_table_raw = [this]()
{
return get_raw_calibration_table(rgb_calibration_id);
return get_d400_raw_calibration_table(d400_calibration_table_id::rgb_calibration_id);
};

_color_extrinsic = std::make_shared<lazy<rs2_extrinsics>>([this]() { return from_pose(get_color_stream_extrinsic(*_color_calib_table_raw)); });
Expand Down Expand Up @@ -120,7 +120,7 @@ namespace librealsense
auto& raw_color_ep = get_raw_color_sensor();

_ds_color_common = std::make_shared<ds_color_common>(raw_color_ep, color_ep,
_fw_version, _hw_monitor, this, ds::ds_device_type::ds5);
_fw_version, _hw_monitor, this);

register_options();
if (_pid != ds::RS457_PID)
Expand Down Expand Up @@ -326,9 +326,9 @@ namespace librealsense

rs2_intrinsics d400_color_sensor::get_intrinsics(const stream_profile& profile) const
{
return get_intrinsic_by_resolution(
return get_d400_intrinsic_by_resolution(
*_owner->_color_calib_table_raw,
ds::calibration_table_id::rgb_calibration_id,
ds::d400_calibration_table_id::rgb_calibration_id,
profile.width, profile.height);
}

Expand Down
Loading