25 #include "../common/fw/firmware-version.h" 28 #include "../common/utilities/time/periodic_timer.h" 29 #include "../common/utilities/time/work_week.h" 30 #include "../common/utilities/time/l500/get-mfr-ww.h" 52 using namespace ivcam2;
66 using namespace ivcam2;
68 auto&& backend = ctx->get_backend();
76 std::make_shared<locked_transfer>(backend.create_usb_device(group.
usb_devices.front()),
82 std::make_shared<locked_transfer>(std::make_shared<command_transfer_over_xu>(
91 std::make_shared<locked_transfer>(std::make_shared<command_transfer_over_xu>(
112 using namespace platform;
114 _usb_mode = raw_depth_sensor.get_usb_specification();
162 const std::vector<platform::uvc_device_info>& all_device_infos )
164 auto&& backend = ctx->get_backend();
166 std::vector<std::shared_ptr<platform::uvc_device>> depth_devices;
168 depth_devices.push_back( backend.create_uvc_device(
info ) );
171 auto enable_global_time_option = std::shared_ptr<global_time_option>(
new global_time_option() );
172 auto raw_depth_ep = std::make_shared<uvc_sensor>(
"Raw Depth Sensor", std::make_shared<platform::multi_pins_uvc_device>( depth_devices ),
174 raw_depth_ep->register_xu(
depth_xu );
213 return (
it != _streams.end() );
216 std::vector< rs2::frame > results )
override {
217 if( results.empty() )
233 auto enable_max_usable_range = std::make_shared<max_usable_range_option>(
this);
236 auto enable_ir_reflectivity = std::make_shared<ir_reflectivity_option>(
this);
272 std::make_shared< ac_trigger::enabler_option >(
_autocal )
276 std::make_shared< ac_trigger::reset_option >(
_autocal )
286 auto sync = std::make_shared<syncer_process_unit>(
nullptr,
false);
288 auto cpb = std::make_shared<composite_processing_block>();
295 cpb->add( std::make_shared< ac_trigger::depth_processing_block >(
_autocal ) );
297 cpb->add( std::make_shared< filtering_processing_block >( RS2_STREAM_DEPTH ) );
312 auto conf = std::make_shared<confidence_rotation_transform>();
313 auto sync = std::make_shared<syncer_process_unit>(
nullptr,
false);
315 auto cpb = std::make_shared<composite_processing_block>();
323 cpb->add( std::make_shared< ac_trigger::depth_processing_block >(
_autocal ) );
325 cpb->add( std::shared_ptr< filtering_processing_block >(
340 []() {
return std::make_shared<confidence_rotation_transform>(); }
346 std::shared_ptr< freefall_option > freefall_opt;
351 freefall_opt = std::make_shared< freefall_option >( *
_hw_monitor )
356 LOG_DEBUG(
"Skipping Freefall control: requires FW 1.3.5" );
362 std::make_shared< hw_sync_option >( *
_hw_monitor, freefall_opt )
367 LOG_DEBUG(
"Skipping HW Sync control: requires FW 1.3.12.9" );
373 std::time_t
now = std::time(
nullptr );
374 auto ptm = localtime( &now );
376 strftime( buf,
sizeof( buf ),
"%T", ptm );
377 AC_LOG(
DEBUG,
".,_,.-'``'-.,_,.-'``'- " << buf <<
" status= " << status );
379 cb->on_calibration_change( status );
388 calibration_type = ac_trigger::calibration_type::AUTO;
391 calibration_type = ac_trigger::calibration_type::MANUAL;
395 to_string() <<
"unsupported calibration type (" << type <<
")" );
401 <<
") does not support depth-to-rgb calibration" );
406 AC_LOG(
INFO,
"Camera Accuracy Health has been manually triggered" );
407 _autocal->trigger_calibration( calibration_type );
429 if (dynamic_cast<const platform::playback_backend*>(&(
get_context()->get_backend())) !=
nullptr)
445 throw std::runtime_error(
"Not enough bytes returned from the firmware!");
460 LOG_INFO(
"entering to update state, device disconnect is expected");
465 for (
auto i = 0;
i < 50;
i++)
469 this_thread::sleep_for(milliseconds(50));
471 throw std::runtime_error(
"Device still connected!");
474 catch (std::exception&
e) {
484 int flash_size = 1024 * 2048;
485 int max_bulk_size = 1016;
486 int max_iterations = int(flash_size / max_bulk_size + 1);
488 std::vector<uint8_t> flash;
489 flash.reserve(flash_size);
493 for (
int i = 0;
i < max_iterations;
i++)
495 int offset = max_bulk_size *
i;
496 int size = max_bulk_size;
497 if (i == max_iterations - 1)
499 size = flash_size -
offset;
502 bool appended =
false;
504 const int retries = 3;
505 for (
int j = 0;
j < retries && !appended;
j++)
514 flash.insert(flash.end(),
res.begin(),
res.end());
519 if (i < retries - 1) std::this_thread::sleep_for(std::chrono::milliseconds(100));
524 if (callback) callback->on_update_progress((
float)i / max_iterations);
526 if (callback) callback->on_update_progress(1.0);
540 sector_count += first_sector;
542 for (
int sector_index = first_sector; sector_index < sector_count; sector_index++)
546 cmdFES.
param1 = int(sector_index);
548 auto res = hwm->send(cmdFES);
552 auto index = sector_index * ivcam2::FLASH_SECTOR_SIZE +
i;
553 if (
index >= offset + size)
559 cmdFWB.
param2 = packet_size;
560 cmdFWB.
data.assign(image.data() +
index, image.data() +
index + packet_size);
561 res = hwm->send(cmdFWB);
566 callback->on_update_progress(continue_from + (
float)sector_index / (
float)sector_count * ratio);
573 auto first_table_offset = fs.
tables.front().offset;
574 float total_size = float(fs.
app_size + tables_size);
576 float app_ratio = fs.
app_size / total_size * ratio;
577 float tables_ratio = tables_size / total_size * ratio;
580 update_flash_section(hwm, merged_image, first_table_offset, tables_size, callback, app_ratio, tables_ratio);
587 auto merged_image =
merge_images(flash_backup_info, flash_image_info, image);
590 auto first_table_offset = flash_image_info.read_write_section.tables.front().offset;
591 auto tables_size = flash_image_info.header.read_write_start_address + flash_image_info.header.read_write_size - first_table_offset;
597 auto first_table_offset = flash_image_info.read_only_section.tables.front().offset;
598 auto tables_size = flash_image_info.header.read_only_start_address + flash_image_info.header.read_only_size - first_table_offset;
599 update_section(hwm, merged_image, flash_image_info.read_only_section, tables_size, callback, 0.5, 0.5);
606 throw std::runtime_error(
"this camera is locked and doesn't allow direct flash write, for firmware update use rs2_update_firmware method (DFU)");
627 throw std::runtime_error(
"invalid update mode value");
630 if (callback) callback->on_update_progress(1.0);
650 if (
res.size() < expected_size)
653 << command_name +
" FW command failed: size expected: " 654 << expected_size <<
" , size received: " <<
res.size());
657 LOG_INFO(command_name <<
": " << static_cast<int>(
res[0]));
662 std::string command_str(input.begin(), input.end());
664 if (command_str ==
"GET-NEST")
682 return std::vector< uint8_t >();
686 to_string() <<
"get-nest command requires FW version >= " << minimal_fw_ver
712 if (
res.size() < expected_size)
714 throw std::runtime_error(
715 to_string() <<
"TEMPERATURES_GET - Invalid result size! expected: " 716 << expected_size <<
" bytes, " 717 "got: " <<
res.size() <<
" bytes");
720 if (fw_version_support_nest)
723 *
reinterpret_cast<temperatures *
>(&rv) = *reinterpret_cast<temperatures const *>(
res.data());
730 LOG_DEBUG(
"Starting temperature fetcher thread");
746 if (second_has_passed)
750 if (
res.size() < expected_size)
752 throw std::runtime_error(
753 to_string() <<
"TEMPERATURES_GET - Invalid result size!, expected: " 754 << expected_size <<
" bytes, " 755 "got: " <<
res.size() <<
" bytes");
761 if (fw_version_support_nest)
770 std::this_thread::sleep_for(std::chrono::milliseconds(300));
775 LOG_WARNING(
"unable to read temperatures - closing temperatures reader");
785 LOG_DEBUG(
"Stopping temperature fetcher thread");
std::shared_ptr< hw_monitor > _hw_monitor
static const textual_icon lock
virtual void register_option(rs2_option id, std::shared_ptr< option > option)
std::vector< uint8_t > backup_flash(update_progress_callback_ptr callback) override
std::shared_ptr< synthetic_sensor > create_depth_device(std::shared_ptr< context > ctx, const std::vector< platform::uvc_device_info > &all_device_infos)
static const double TIMESTAMP_USEC_TO_MSEC
static void log_FW_response_first_byte(hw_monitor &hwm, const std::string &command_name, const command &cmd, size_t expected_size)
static const std::map< std::uint16_t, std::string > rs500_sku_names
ivcam2::extended_temperatures _temperatures
auto invoke_powered(T action) -> decltype(action(*static_cast< platform::uvc_device * >(nullptr)))
filtering_processing_block(rs2_stream stream_to_pass)
void start_temperatures_reader()
notification decode(int value) override
void notify_of_calibration_change(rs2_calibration_status status)
void register_processing_block(const std::vector< stream_profile > &from, const std::vector< stream_profile > &to, std::function< std::shared_ptr< processing_block >(void)> generate_func)
unsigned char weeks_since_calibration
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
std::atomic_bool _have_temperatures
virtual l500_color_sensor * get_color_sensor()=0
stream_profile get_profile() const
void enter_update_state() const override
void enable_recording(std::function< void(const debug_interface &)> record_action) override
const uint32_t FLASH_SIZE
double get_device_time_ms() override
utilities::time::work_week get_manufacture_work_week(const std::string &serial)
std::mutex _temperature_mutex
GLsizei const GLchar *const * string
platform::usb_spec _usb_mode
filtering_processing_block(std::initializer_list< rs2_stream > const &streams)
resolution l500_confidence_resolution(resolution res)
void update_flash_internal(std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &image, std::vector< uint8_t > &flash_backup, update_progress_callback_ptr callback, int update_mode)
void trigger_device_calibration(rs2_calibration_type) override
GLenum GLenum GLsizei void * image
status
Defines return codes that SDK interfaces use. Negative values indicate errors, a zero value indicates...
std::shared_ptr< ivcam2::ac_trigger > _autocal
uint8_t _depth_device_idx
std::shared_ptr< rs2_update_progress_callback > update_progress_callback_ptr
GLenum GLuint GLenum GLsizei const GLchar * buf
def info(name, value, persistent=False)
std::shared_ptr< time_diff_keeper > _tf_keeper
firmware_version _fw_version
std::string hexify(const T &val)
bool should_process(const rs2::frame &f) override
void register_info(rs2_camera_info info, const std::string &val)
void update_section(std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &merged_image, flash_section fs, uint32_t tables_size, update_progress_callback_ptr callback, float continue_from, float ratio)
#define RS2_UNSIGNED_UPDATE_MODE_UPDATE
const uint32_t FLASH_SECTOR_SIZE
std::vector< uint8_t > send(std::vector< uint8_t > const &data) const
const std::map< uint8_t, std::string > l500_fw_error_report
l500_depth_sensor & get_depth_sensor()
uint32_t rs_fourcc(const T a, const T b, const T c, const T d)
#define RS2_UNSIGNED_UPDATE_MODE_READ_ONLY
frame allocate_composite_frame(std::vector< frame > frames) const
command get_flash_logs_command() const
static processing_block_factory create_id_pbf(rs2_format format, rs2_stream stream, int idx=0)
std::vector< uint8_t > data
virtual void configure_depth_options()
std::map< uint32_t, rs2_format > l500_depth_fourcc_to_rs2_format
std::vector< uint8_t > merge_images(flash_info from, flash_info to, const std::vector< uint8_t > image)
flash_info get_flash_info(const std::vector< uint8_t > &flash_buffer)
std::map< uint32_t, rs2_stream > l500_depth_fourcc_to_rs2_stream
#define L5XX_RECOMMENDED_FIRMWARE_VERSION
uvc_sensor & get_raw_depth_sensor()
unsigned get_work_weeks_since(const work_week &start)
const uint8_t L500_HWMONITOR
rs2::frame prepare_output(const rs2::frame_source &source, rs2::frame input, std::vector< rs2::frame > results) override
const platform::extension_unit depth_xu
const std::string & get_info(rs2_camera_info info) const override
resolution rotate_resolution(resolution res)
rs2_stream
Streams are different types of data provided by RealSense devices.
int add_sensor(const std::shared_ptr< sensor_interface > &sensor_base)
#define AC_LOG(TYPE, MSG)
unsigned char ac_weeks_since_calibaration
#define RS2_UNSIGNED_UPDATE_MODE_FULL
command get_firmware_logs_command() const
sensor_interface & get_sensor(size_t subdevice) override
std::vector< uint8_t > send_receive_raw_data(const std::vector< uint8_t > &input) override
void stop_temperatures_reader()
LOG_INFO("Log message using LOG_INFO()")
GLuint GLfloat GLfloat GLfloat x1
const uint16_t HW_MONITOR_COMMAND_SIZE
std::shared_ptr< context > get_context() const override
void override_dsm_params(rs2_dsm_params const &dsm_params) override
GLenum GLenum GLenum input
std::thread _temperature_reader
std::vector< flash_table > tables
void update_flash(const std::vector< uint8_t > &image, update_progress_callback_ptr callback, int update_mode) override
rs2::frame process_frame(const rs2::frame_source &source, const rs2::frame &f) override
std::vector< calibration_change_callback_ptr > _calibration_change_callbacks
std::vector< rs2_stream > _streams
typename::boost::move_detail::remove_reference< T >::type && move(T &&t) BOOST_NOEXCEPT
GLsizei GLsizei GLchar * source
const int REGISTER_CLOCK_0
void create_snapshot(std::shared_ptr< debug_interface > &snapshot) const override
std::vector< platform::uvc_device_info > filter_by_mi(const std::vector< platform::uvc_device_info > &devices, uint32_t mi)
const uint16_t HW_MONITOR_BUFFER_SIZE
void force_hardware_reset() const
rs2_stream stream_type() const
l500_device(std::shared_ptr< context > ctx, const platform::backend_device_group &group)
virtual void stop_activity() const
std::atomic_bool _keep_reading_temperature
void update_flash_section(std::shared_ptr< hw_monitor > hwm, const std::vector< uint8_t > &image, uint32_t offset, uint32_t size, update_progress_callback_ptr callback, float continue_from, float ratio)
ivcam2::extended_temperatures get_temperatures() const
std::string to_string(T value)