auto-calibrated-device.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2019 Intel Corporation. All Rights Reserved.
3 
4 #pragma once
5 
6 #include "types.h"
7 #include "core/streaming.h"
8 
9 namespace librealsense
10 {
12  {
13  public:
14  virtual void write_calibration() const = 0;
15  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;
16  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;
17  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;
18  virtual std::vector<uint8_t> get_calibration_table() const = 0;
19  virtual void set_calibration_table(const std::vector<uint8_t>& calibration) = 0;
20  virtual void reset_to_factory_calibration() const = 0;
21  virtual std::vector<uint8_t> run_focal_length_calibration(rs2_frame_queue* left, rs2_frame_queue* right, float target_w, float target_h,
22  int adjust_both_sides, float* ratio, float* angle, update_progress_callback_ptr progress_callback) = 0;
23  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,
24  float* const health, int health_size, update_progress_callback_ptr progress_callback) = 0;
25  virtual float calculate_target_z(rs2_frame_queue* queue1, rs2_frame_queue* queue2, rs2_frame_queue* queue3,
26  float target_w, float target_h, update_progress_callback_ptr progress_callback) = 0;
27  };
29 }
example1 - object detection.left
left
Definition: example1 - object detection.py:70
color
GLuint color
Definition: glad/glad/glad.h:3181
librealsense
Definition: calibration-model.h:9
librealsense::json
nlohmann::json json
Definition: json_loader.hpp:23
librealsense::auto_calibrated_interface::set_calibration_table
virtual void set_calibration_table(const std::vector< uint8_t > &calibration)=0
librealsense::auto_calibrated_interface::write_calibration
virtual void write_calibration() const =0
librealsense::MAP_EXTENSION
MAP_EXTENSION(RS2_EXTENSION_AUTO_CALIBRATED_DEVICE, auto_calibrated_interface)
librealsense::auto_calibrated_interface::get_calibration_table
virtual std::vector< uint8_t > get_calibration_table() const =0
streaming.h
rs2_frame
struct rs2_frame rs2_frame
Definition: rs_types.h:262
right
GLdouble right
Definition: glad/glad/glad.h:2249
librealsense::auto_calibrated_interface::reset_to_factory_calibration
virtual void reset_to_factory_calibration() const =0
rs2_frame_queue
Definition: rs.cpp:110
librealsense::auto_calibrated_interface::run_uv_map_calibration
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
librealsense::auto_calibrated_interface::run_tare_calibration
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
f
GLdouble f
Definition: glad/glad/glad.h:1517
depth_auto_calibration_example.progress_callback
def progress_callback(progress)
Definition: depth_auto_calibration_example.py:96
angle
cv::RotateFlags angle(cv::RotateFlags::ROTATE_90_CLOCKWISE)
librealsense::auto_calibrated_interface::calculate_target_z
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
librealsense::auto_calibrated_interface::run_focal_length_calibration
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
librealsense::auto_calibrated_interface::run_on_chip_calibration
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
RS2_EXTENSION_AUTO_CALIBRATED_DEVICE
@ RS2_EXTENSION_AUTO_CALIBRATED_DEVICE
Definition: rs_types.h:209
librealsense::auto_calibrated_interface::process_calibration_frame
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
librealsense::auto_calibrated_interface
Definition: auto-calibrated-device.h:11
types.h
depth
GLint GLint GLsizei GLsizei GLsizei depth
Definition: glad/glad/glad.h:2398
librealsense::update_progress_callback_ptr
std::shared_ptr< rs2_update_progress_callback > update_progress_callback_ptr
Definition: src/types.h:885


librealsense2
Author(s): LibRealSense ROS Team
autogenerated on Thu Dec 22 2022 03:13:13