#include <ac-trigger.h>
Classes | |
class | ac_logger |
class | color_processing_block |
class | depth_processing_block |
class | enabler_option |
class | next_trigger |
class | reset_option |
class | retrier |
class | temp_check |
Public Types | |
enum | calibration_type { calibration_type::MANUAL, calibration_type::AUTO } |
using | callback = std::function< void(rs2_calibration_status) > |
Public Member Functions | |
ac_trigger (l500_device &dev, std::shared_ptr< hw_monitor > hwm) | |
bool | auto_calibration_is_on () const |
rs2_dsm_params const & | get_dsm_params () const |
rs2_extrinsics const & | get_extrinsics () const |
stream_profile_interface * | get_from_profile () const |
rs2_intrinsics const & | get_raw_intrinsics () const |
rs2_intrinsics const & | get_thermal_intrinsics () const |
stream_profile_interface * | get_to_profile () const |
bool | is_active () const |
void | register_callback (callback cb) |
void | start () |
void | stop () |
void | trigger_calibration (calibration_type type) |
~ac_trigger () | |
Private Member Functions | |
void | _start () |
void | calibration_is_done () |
void | call_back (rs2_calibration_status status) |
void | cancel_current_calibration () |
bool | check_color_depth_sync () |
void | check_conditions () |
ac_logger & | get_ac_logger () |
bool | is_expecting_special_frame () const |
bool | is_processing () const |
double | read_temperature () |
void | reset () |
void | run_algo () |
void | schedule_next_calibration () |
void | schedule_next_temp_trigger () |
void | schedule_next_time_trigger (std::chrono::seconds n_seconds=std::chrono::seconds(0)) |
void | set_color_frame (rs2::frame const &) |
void | set_not_active () |
void | set_special_frame (rs2::frameset const &) |
void | start_color_sensor_if_needed () |
void | stop_color_sensor_if_started () |
void | trigger_retry () |
void | trigger_special_frame () |
Private Attributes | |
calibration_type | _calibration_type |
std::vector< callback > | _callbacks |
rs2::frame | _cf |
l500_device & | _dev |
rs2_digital_gain | _digital_gain |
rs2_dsm_params | _dsm_params |
rs2_extrinsics | _extr |
stream_profile_interface * | _from_profile = nullptr |
std::weak_ptr< hw_monitor > | _hwm |
bool | _is_on = false |
std::atomic_bool | _is_processing {false} |
rs2_calibration_status | _last_status_sent |
double | _last_temp = 0 |
std::vector< uint16_t > | _last_yuy_data |
std::mutex | _mutex |
unsigned | _n_cycles = 0 |
unsigned | _n_retries |
bool | _need_to_wait_for_color_sensor_stability = false |
std::shared_ptr< next_trigger > | _next_trigger |
rs2::frame | _pcf |
rs2_intrinsics | _raw_intr |
int | _receiver_gain |
std::shared_ptr< retrier > | _recycler |
std::shared_ptr< retrier > | _retrier |
std::chrono::high_resolution_clock::time_point | _rgb_sensor_start |
rs2::frameset | _sf |
double | _temp |
std::shared_ptr< temp_check > | _temp_check |
rs2_intrinsics | _thermal_intr |
stream_profile_interface * | _to_profile = nullptr |
std::thread | _worker |
Definition at line 22 of file ac-trigger.h.
using librealsense::ivcam2::ac_trigger::callback = std::function< void( rs2_calibration_status ) > |
Definition at line 182 of file ac-trigger.h.
Enumerator | |
---|---|
MANUAL | |
AUTO |
Definition at line 139 of file ac-trigger.h.
librealsense::ivcam2::ac_trigger::ac_trigger | ( | l500_device & | dev, |
std::shared_ptr< hw_monitor > | hwm | ||
) |
Definition at line 599 of file ac-trigger.cpp.
librealsense::ivcam2::ac_trigger::~ac_trigger | ( | ) |
Definition at line 616 of file ac-trigger.cpp.
|
private |
Definition at line 1385 of file ac-trigger.cpp.
|
inline |
Definition at line 170 of file ac-trigger.h.
|
private |
Definition at line 1169 of file ac-trigger.cpp.
|
private |
Definition at line 627 of file ac-trigger.cpp.
|
private |
Definition at line 1148 of file ac-trigger.cpp.
|
private |
Definition at line 908 of file ac-trigger.cpp.
|
private |
Definition at line 1243 of file ac-trigger.cpp.
|
private |
Definition at line 607 of file ac-trigger.cpp.
|
inline |
Definition at line 178 of file ac-trigger.h.
|
inline |
Definition at line 175 of file ac-trigger.h.
|
inline |
Definition at line 179 of file ac-trigger.h.
|
inline |
Definition at line 176 of file ac-trigger.h.
|
inline |
Definition at line 177 of file ac-trigger.h.
|
inline |
Definition at line 180 of file ac-trigger.h.
|
inline |
Definition at line 161 of file ac-trigger.h.
|
inlineprivate |
Definition at line 196 of file ac-trigger.h.
|
inlineprivate |
Definition at line 195 of file ac-trigger.h.
|
private |
Definition at line 1237 of file ac-trigger.cpp.
Definition at line 183 of file ac-trigger.h.
Definition at line 1434 of file ac-trigger.cpp.
|
private |
Definition at line 940 of file ac-trigger.cpp.
|
private |
Definition at line 1192 of file ac-trigger.cpp.
|
private |
Definition at line 1221 of file ac-trigger.cpp.
|
private |
Definition at line 1205 of file ac-trigger.cpp.
|
private |
Definition at line 866 of file ac-trigger.cpp.
|
private |
Definition at line 1185 of file ac-trigger.cpp.
|
private |
Definition at line 822 of file ac-trigger.cpp.
void librealsense::ivcam2::ac_trigger::start | ( | ) |
Definition at line 1363 of file ac-trigger.cpp.
|
private |
Definition at line 763 of file ac-trigger.cpp.
void librealsense::ivcam2::ac_trigger::stop | ( | ) |
Definition at line 1411 of file ac-trigger.cpp.
|
private |
Definition at line 797 of file ac-trigger.cpp.
void librealsense::ivcam2::ac_trigger::trigger_calibration | ( | calibration_type | type | ) |
Definition at line 714 of file ac-trigger.cpp.
|
private |
Definition at line 635 of file ac-trigger.cpp.
|
private |
Definition at line 691 of file ac-trigger.cpp.
|
private |
Definition at line 146 of file ac-trigger.h.
|
private |
Definition at line 211 of file ac-trigger.h.
|
private |
Definition at line 25 of file ac-trigger.h.
|
private |
Definition at line 32 of file ac-trigger.h.
|
private |
Definition at line 27 of file ac-trigger.h.
|
private |
Definition at line 44 of file ac-trigger.h.
|
private |
Definition at line 41 of file ac-trigger.h.
|
private |
Definition at line 45 of file ac-trigger.h.
|
private |
Definition at line 31 of file ac-trigger.h.
|
private |
Definition at line 34 of file ac-trigger.h.
|
private |
Definition at line 36 of file ac-trigger.h.
|
private |
Definition at line 52 of file ac-trigger.h.
|
private |
Definition at line 58 of file ac-trigger.h.
|
private |
Definition at line 47 of file ac-trigger.h.
|
private |
Definition at line 35 of file ac-trigger.h.
|
private |
Definition at line 39 of file ac-trigger.h.
|
private |
Definition at line 38 of file ac-trigger.h.
|
private |
Definition at line 61 of file ac-trigger.h.
|
private |
Definition at line 54 of file ac-trigger.h.
|
private |
Definition at line 25 of file ac-trigger.h.
|
private |
Definition at line 42 of file ac-trigger.h.
|
private |
Definition at line 28 of file ac-trigger.h.
|
private |
Definition at line 51 of file ac-trigger.h.
|
private |
Definition at line 49 of file ac-trigger.h.
|
private |
Definition at line 62 of file ac-trigger.h.
|
private |
Definition at line 24 of file ac-trigger.h.
|
private |
Definition at line 29 of file ac-trigger.h.
|
private |
Definition at line 59 of file ac-trigger.h.
|
private |
Definition at line 43 of file ac-trigger.h.
|
private |
Definition at line 46 of file ac-trigger.h.
|
private |
Definition at line 37 of file ac-trigger.h.