l500-device.cpp
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2018 Intel Corporation. All Rights Reserved.
3 
4 #include "l500-device.h"
5 
6 #include <vector>
7 
8 #include "context.h"
9 #include "stream.h"
10 #include "image.h"
11 
12 #include "l500-depth.h"
13 #include "l500-color.h"
14 #include "l500-private.h"
15 
16 #include "proc/decimation-filter.h"
17 #include "proc/threshold.h"
18 #include "proc/spatial-filter.h"
19 #include "proc/temporal-filter.h"
21 #include "proc/zero-order.h"
25 #include "../common/fw/firmware-version.h"
26 #include "ac-trigger.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"
31 
32 
33 
34 namespace librealsense
35 {
36  std::map<uint32_t, rs2_format> l500_depth_fourcc_to_rs2_format = {
37  { rs_fourcc('G','R','E','Y'), RS2_FORMAT_Y8 },
38  { rs_fourcc('Z','1','6',' '), RS2_FORMAT_Z16 },
39  { rs_fourcc('C',' ',' ',' '), RS2_FORMAT_RAW8 },
40  { rs_fourcc('C','N','F','4'), RS2_FORMAT_RAW8 },
41  { rs_fourcc('F','G',' ',' '), RS2_FORMAT_FG },
42  };
43 
44  std::map<uint32_t, rs2_stream> l500_depth_fourcc_to_rs2_stream = {
45  { rs_fourcc('G','R','E','Y'), RS2_STREAM_INFRARED },
46  { rs_fourcc('Z','1','6',' '), RS2_STREAM_DEPTH },
47  { rs_fourcc('C',' ',' ',' '), RS2_STREAM_CONFIDENCE },
48  { rs_fourcc('C','N','F','4'), RS2_STREAM_CONFIDENCE },
49  { rs_fourcc('F','G',' ',' '), RS2_STREAM_DEPTH },
50  };
51 
52  using namespace ivcam2;
53 
54  l500_device::l500_device(std::shared_ptr<context> ctx,
56  :device(ctx, group), global_time_interface(),
57  _depth_stream(new stream(RS2_STREAM_DEPTH)),
58  _ir_stream(new stream(RS2_STREAM_INFRARED)),
59  _confidence_stream(new stream(RS2_STREAM_CONFIDENCE)),
60  _temperatures()
61  {
63  auto pid = group.uvc_devices.front().pid;
64  std::string device_name = (rs500_sku_names.end() != rs500_sku_names.find(pid)) ? rs500_sku_names.at(pid) : "RS5xx";
65 
66  using namespace ivcam2;
67 
68  auto&& backend = ctx->get_backend();
69 
71  auto& raw_depth_sensor = get_raw_depth_sensor();
72 
73  if (group.usb_devices.size() > 0)
74  {
75  _hw_monitor = std::make_shared<hw_monitor>(
76  std::make_shared<locked_transfer>(backend.create_usb_device(group.usb_devices.front()),
77  raw_depth_sensor));
78  }
79  else
80  {
81  _hw_monitor = std::make_shared<hw_monitor>(
82  std::make_shared<locked_transfer>(std::make_shared<command_transfer_over_xu>(
83  raw_depth_sensor, depth_xu, L500_HWMONITOR),
84  raw_depth_sensor));
85  }
86 
87 #ifdef HWM_OVER_XU
88  if (group.usb_devices.size() > 0)
89  {
90  _hw_monitor = std::make_shared<hw_monitor>(
91  std::make_shared<locked_transfer>(std::make_shared<command_transfer_over_xu>(
92  raw_depth_sensor, depth_xu, L500_HWMONITOR),
93  raw_depth_sensor));
94  }
95 #endif
96 
97  std::vector<uint8_t> gvd_buff(HW_MONITOR_BUFFER_SIZE);
98  _hw_monitor->get_gvd(gvd_buff.size(), gvd_buff.data(), GVD);
99  // fooling tests recordings - don't remove
100  _hw_monitor->get_gvd(gvd_buff.size(), gvd_buff.data(), GVD);
101 
102  auto optic_serial = _hw_monitor->get_module_serial_string(gvd_buff, module_serial_offset, module_serial_size);
103  auto asic_serial = _hw_monitor->get_module_serial_string(gvd_buff, module_asic_serial_offset, module_asic_serial_size);
104  auto fwv = _hw_monitor->get_firmware_version_string(gvd_buff, fw_version_offset);
106  firmware_version recommended_fw_version(L5XX_RECOMMENDED_FIRMWARE_VERSION);
107 
108  _is_locked = _hw_monitor->get_gvd_field<uint8_t>(gvd_buff, is_camera_locked_offset) != 0;
109 
110  auto pid_hex_str = hexify(group.uvc_devices.front().pid);
111 
112  using namespace platform;
113 
114  _usb_mode = raw_depth_sensor.get_usb_specification();
115  if (usb_spec_names.count(_usb_mode) && (usb_undefined != _usb_mode))
116  {
117  auto usb_type_str = usb_spec_names.at(_usb_mode);
119  }
120 
121  register_info(RS2_CAMERA_INFO_NAME, device_name);
128  register_info(RS2_CAMERA_INFO_PHYSICAL_PORT, group.uvc_devices.front().device_path);
132 
133  // If FW supportes the SET_AGE command, we update the age of the device in weeks to aid projection of aging
134  if( ( _fw_version >= firmware_version( "1.5.4.0" ) ) )
135  {
136  try
137  {
138  auto manufacture
140  auto age
141  = utilities::time::get_work_weeks_since( manufacture );
143  _hw_monitor->send( cmd );
144  }
145  catch( ... )
146  {
147  LOG_ERROR( "Failed to set units age" );
148  }
149  }
150 
152  }
153 
154 
156  {
157  return dynamic_cast<l500_depth_sensor &>(get_sensor( _depth_device_idx ));
158  }
159 
160 
161  std::shared_ptr<synthetic_sensor> l500_device::create_depth_device( std::shared_ptr<context> ctx,
162  const std::vector<platform::uvc_device_info>& all_device_infos )
163  {
164  auto&& backend = ctx->get_backend();
165 
166  std::vector<std::shared_ptr<platform::uvc_device>> depth_devices;
167  for( auto&& info : filter_by_mi( all_device_infos, 0 ) ) // Filter just mi=0, DEPTH
168  depth_devices.push_back( backend.create_uvc_device( info ) );
169 
170  std::unique_ptr<frame_timestamp_reader> timestamp_reader_metadata( new l500_timestamp_reader_from_metadata( backend.create_time_service() ) );
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 ),
173  std::unique_ptr<frame_timestamp_reader>( new global_timestamp_reader( std::move( timestamp_reader_metadata ), _tf_keeper, enable_global_time_option ) ), this );
174  raw_depth_ep->register_xu( depth_xu );
175 
176  auto depth_ep = std::make_shared<l500_depth_sensor>( this, raw_depth_ep, l500_depth_fourcc_to_rs2_format, l500_depth_fourcc_to_rs2_stream );
177 
178  depth_ep->register_option( RS2_OPTION_GLOBAL_TIME_ENABLED, enable_global_time_option );
179  depth_ep->get_option( RS2_OPTION_GLOBAL_TIME_ENABLED ).set( 0 );
180 
181  // NOTE: _fw_version is not yet initialized! Any additional options should get added from configure_depth_options()!
182  depth_ep->register_info(RS2_CAMERA_INFO_PHYSICAL_PORT, filter_by_mi(all_device_infos, 0).front().device_path);
183  return depth_ep;
184  }
185 
186 
194  std::vector< rs2_stream > _streams;
195 
196  public:
198  : generic_processing_block( "filtering_processing_block" ), _streams( 1, stream_to_pass ) {}
199  filtering_processing_block( std::initializer_list< rs2_stream > const & streams )
200  : generic_processing_block( "filtering_processing_block" ), _streams( streams ) {}
201 
203  const rs2::frame & f ) override {
204  return f;
205  }
206 
207  private:
208  bool should_process( const rs2::frame & f ) override {
209  auto fs = f.as< rs2::frameset >();
210  if( fs )
211  return false; // we'll get the individual frames back by themselves:
212  auto it = std::find( _streams.begin(), _streams.end(), f.get_profile().stream_type() );
213  return ( it != _streams.end() ); // keep the frame only if one of those we got
214  }
216  std::vector< rs2::frame > results ) override {
217  if( results.empty() )
218  return rs2::frame{};
219  return source.allocate_composite_frame(results);
220  }
221  };
222 
223 
225  {
227 
228  if( _fw_version >= firmware_version( "1.5.0.0" ) )
229  {
231  if (usb3mode)
232  {
233  auto enable_max_usable_range = std::make_shared<max_usable_range_option>(this);
234  depth_sensor.register_option(RS2_OPTION_ENABLE_MAX_USABLE_RANGE, enable_max_usable_range);
235 
236  auto enable_ir_reflectivity = std::make_shared<ir_reflectivity_option>(this);
237  depth_sensor.register_option(RS2_OPTION_ENABLE_IR_REFLECTIVITY, enable_ir_reflectivity);
238  }
239 
240  // TODO may not need auto-cal if there's no color sensor, like on the rs500...
241  _autocal = std::make_shared< ac_trigger >( *this, _hw_monitor );
242 
243  // Have the auto-calibration mechanism notify us when calibration has finished
244  _autocal->register_callback(
246  {
247  if( status == RS2_CALIBRATION_SUCCESSFUL )
248  {
249  rs2_dsm_params new_dsm_params = _autocal->get_dsm_params();
250  // We update the age of the device in weeks and the time between factory
251  // calibration and last AC to aid projection
254  auto age
255  = utilities::time::get_work_weeks_since( manufacture );
256  new_dsm_params.weeks_since_calibration = (uint8_t)age;
257  new_dsm_params.ac_weeks_since_calibaration = (uint8_t)age;
258 
259  // We override the DSM params first, because it can throw if the parameters
260  // are exceeding spec! This may throw!!
261  get_depth_sensor().override_dsm_params( new_dsm_params );
262  auto & color_sensor = *get_color_sensor();
263  color_sensor.override_intrinsics( _autocal->get_raw_intrinsics() );
264  color_sensor.override_extrinsics( _autocal->get_extrinsics() );
265  color_sensor.set_k_thermal_intrinsics( _autocal->get_thermal_intrinsics() );
266  }
268  } );
269 
270  depth_sensor.register_option(
272  std::make_shared< ac_trigger::enabler_option >( _autocal )
273  );
274  depth_sensor.register_option(
276  std::make_shared< ac_trigger::reset_option >( _autocal )
277  );
278  }
279 
280  depth_sensor.register_processing_block(
281  { {RS2_FORMAT_Z16}, {RS2_FORMAT_Y8} },
283  [=]() {
284  auto z16rot = std::make_shared<rotation_transform>(RS2_FORMAT_Z16, RS2_STREAM_DEPTH, RS2_EXTENSION_DEPTH_FRAME);
285  auto y8rot = std::make_shared<rotation_transform>(RS2_FORMAT_Y8, RS2_STREAM_INFRARED, RS2_EXTENSION_VIDEO_FRAME);
286  auto sync = std::make_shared<syncer_process_unit>(nullptr, false); // disable logging on this internal syncer
287 
288  auto cpb = std::make_shared<composite_processing_block>();
289  cpb->add(z16rot);
290  cpb->add(y8rot);
291  cpb->add(sync);
292  if( _autocal )
293  {
294  //sync->add_enabling_option( _autocal->get_enabler_opt() );
295  cpb->add( std::make_shared< ac_trigger::depth_processing_block >( _autocal ) );
296  }
297  cpb->add( std::make_shared< filtering_processing_block >( RS2_STREAM_DEPTH ) );
298  return cpb;
299  }
300  );
301 
302 
303  depth_sensor.register_processing_block(
305  {
306  {RS2_FORMAT_Z16, RS2_STREAM_DEPTH, 0, 0, 0, 0, &rotate_resolution},
308  },
309  [=]() {
310  auto z16rot = std::make_shared<rotation_transform>(RS2_FORMAT_Z16, RS2_STREAM_DEPTH, RS2_EXTENSION_DEPTH_FRAME);
311  auto y8rot = std::make_shared<rotation_transform>(RS2_FORMAT_Y8, RS2_STREAM_INFRARED, RS2_EXTENSION_VIDEO_FRAME);
312  auto conf = std::make_shared<confidence_rotation_transform>();
313  auto sync = std::make_shared<syncer_process_unit>(nullptr, false); // disable logging on this internal syncer
314 
315  auto cpb = std::make_shared<composite_processing_block>();
316  cpb->add(z16rot);
317  cpb->add(y8rot);
318  cpb->add(conf);
319  cpb->add(sync);
320  if( _autocal )
321  {
322  //sync->add_enabling_option( _autocal->get_enabler_opt() );
323  cpb->add( std::make_shared< ac_trigger::depth_processing_block >( _autocal ) );
324  }
325  cpb->add( std::shared_ptr< filtering_processing_block >(
327  return cpb;
328  }
329  );
330 
331  depth_sensor.register_processing_block(
332  { {RS2_FORMAT_Y8} },
333  { {RS2_FORMAT_Y8, RS2_STREAM_INFRARED, 0, 0, 0, 0, &rotate_resolution} },
334  []() { return std::make_shared<rotation_transform>(RS2_FORMAT_Y8, RS2_STREAM_INFRARED, RS2_EXTENSION_VIDEO_FRAME); }
335  );
336 
337  depth_sensor.register_processing_block(
338  { {RS2_FORMAT_RAW8} },
339  { {RS2_FORMAT_RAW8, RS2_STREAM_CONFIDENCE, 0, 0, 0, 0, &l500_confidence_resolution} },
340  []() { return std::make_shared<confidence_rotation_transform>(); }
341  );
342 
343  depth_sensor.register_processing_block(
345 
346  std::shared_ptr< freefall_option > freefall_opt;
347  if( _fw_version >= firmware_version( "1.3.5.0" ) )
348  {
349  depth_sensor.register_option(
351  freefall_opt = std::make_shared< freefall_option >( *_hw_monitor )
352  );
353  }
354  else
355  {
356  LOG_DEBUG( "Skipping Freefall control: requires FW 1.3.5" );
357  }
358  if( _fw_version >= firmware_version( "1.3.12.9" ) )
359  {
360  depth_sensor.register_option(
362  std::make_shared< hw_sync_option >( *_hw_monitor, freefall_opt )
363  );
364  }
365  else
366  {
367  LOG_DEBUG( "Skipping HW Sync control: requires FW 1.3.12.9" );
368  }
369  }
370 
372  {
373  std::time_t now = std::time( nullptr );
374  auto ptm = localtime( &now );
375  char buf[256];
376  strftime( buf, sizeof( buf ), "%T", ptm );
377  AC_LOG( DEBUG, ".,_,.-'``'-.,_,.-'``'- " << buf << " status= " << status );
378  for( auto&& cb : _calibration_change_callbacks )
379  cb->on_calibration_change( status );
380  }
381 
383  {
384  ac_trigger::calibration_type calibration_type;
385  switch( type )
386  {
388  calibration_type = ac_trigger::calibration_type::AUTO;
389  break;
391  calibration_type = ac_trigger::calibration_type::MANUAL;
392  break;
393  default:
395  to_string() << "unsupported calibration type (" << type << ")" );
396  }
397 
398  if( !_autocal )
400  to_string() << "the current firmware version (" << _fw_version
401  << ") does not support depth-to-rgb calibration" );
402 
403  if( _autocal->is_active() )
404  throw wrong_api_call_sequence_exception( "Camera Accuracy Health is already active" );
405 
406  AC_LOG( INFO, "Camera Accuracy Health has been manually triggered" );
407  _autocal->trigger_calibration( calibration_type );
408  }
409 
411  {
413  cmd.require_response = false;
414  _hw_monitor->send(cmd);
415  }
416 
417  void l500_device::create_snapshot(std::shared_ptr<debug_interface>& snapshot) const
418  {
419  throw not_implemented_exception("create_snapshot(...) not implemented!");
420  }
421 
422  void l500_device::enable_recording(std::function<void(const debug_interface&)> record_action)
423  {
424  throw not_implemented_exception("enable_recording(...) not implemented!");
425  }
426 
428  {
429  if (dynamic_cast<const platform::playback_backend*>(&(get_context()->get_backend())) != nullptr)
430  {
431  throw not_implemented_exception("device time not supported for backend.");
432  }
433 
434  if (!_hw_monitor)
435  throw wrong_api_call_sequence_exception("_hw_monitor is not initialized yet");
436 
438  // TODO -Redirect HW Monitor commands to used atomic (UVC) transfers for faster transactions and transfer integrity
439  // Disabled due to limitation in FW
440  auto res = _hw_monitor->send(cmd, nullptr);
441 
442  if (res.size() < sizeof(uint32_t))
443  {
444  LOG_DEBUG("size(res):" << res.size());
445  throw std::runtime_error("Not enough bytes returned from the firmware!");
446  }
447  uint32_t dt = *(uint32_t*)res.data();
448  double ts = dt * TIMESTAMP_USEC_TO_MSEC;
449  return ts;
450  }
451 
453  {
454  // Stop all data streaming/exchange pipes with HW
455  stop_activity();
456  using namespace std;
457  using namespace std::chrono;
458 
459  try {
460  LOG_INFO("entering to update state, device disconnect is expected");
462  cmd.param1 = 1;
463  _hw_monitor->send(cmd);
464  std::vector<uint8_t> gvd_buff(HW_MONITOR_BUFFER_SIZE);
465  for (auto i = 0; i < 50; i++)
466  {
467 
468  _hw_monitor->get_gvd(gvd_buff.size(), gvd_buff.data(), GVD);
469  this_thread::sleep_for(milliseconds(50));
470  }
471  throw std::runtime_error("Device still connected!");
472 
473  }
474  catch (std::exception& e) {
475  LOG_WARNING(e.what());
476  }
477  catch (...) {
478  // The set command returns a failure because switching to DFU resets the device while the command is running.
479  }
480  }
481 
483  {
484  int flash_size = 1024 * 2048;
485  int max_bulk_size = 1016;
486  int max_iterations = int(flash_size / max_bulk_size + 1);
487 
488  std::vector<uint8_t> flash;
489  flash.reserve(flash_size);
490 
492  {
493  for (int i = 0; i < max_iterations; i++)
494  {
495  int offset = max_bulk_size * i;
496  int size = max_bulk_size;
497  if (i == max_iterations - 1)
498  {
499  size = flash_size - offset;
500  }
501 
502  bool appended = false;
503 
504  const int retries = 3;
505  for (int j = 0; j < retries && !appended; j++)
506  {
507  try
508  {
510  cmd.param1 = offset;
511  cmd.param2 = size;
512  auto res = _hw_monitor->send(cmd);
513 
514  flash.insert(flash.end(), res.begin(), res.end());
515  appended = true;
516  }
517  catch (...)
518  {
519  if (i < retries - 1) std::this_thread::sleep_for(std::chrono::milliseconds(100));
520  else throw;
521  }
522  }
523 
524  if (callback) callback->on_update_progress((float)i / max_iterations);
525  }
526  if (callback) callback->on_update_progress(1.0);
527  });
528 
529  return flash;
530  }
531 
532  void l500_device::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)
533  {
534  int sector_count = int( size / ivcam2::FLASH_SECTOR_SIZE );
535  int first_sector = int( offset / ivcam2::FLASH_SECTOR_SIZE );
536 
537  if (sector_count * ivcam2::FLASH_SECTOR_SIZE != size)
538  sector_count++;
539 
540  sector_count += first_sector;
541 
542  for (int sector_index = first_sector; sector_index < sector_count; sector_index++)
543  {
544  command cmdFES(ivcam2::FES);
545  cmdFES.require_response = false;
546  cmdFES.param1 = int(sector_index);
547  cmdFES.param2 = 1;
548  auto res = hwm->send(cmdFES);
549 
550  for (int i = 0; i < ivcam2::FLASH_SECTOR_SIZE; )
551  {
552  auto index = sector_index * ivcam2::FLASH_SECTOR_SIZE + i;
553  if (index >= offset + size)
554  break;
555  int packet_size = std::min((int)(HW_MONITOR_COMMAND_SIZE - (i % HW_MONITOR_COMMAND_SIZE)), (int)(ivcam2::FLASH_SECTOR_SIZE - i));
556  command cmdFWB(ivcam2::FWB);
557  cmdFWB.require_response = false;
558  cmdFWB.param1 = int(index);
559  cmdFWB.param2 = packet_size;
560  cmdFWB.data.assign(image.data() + index, image.data() + index + packet_size);
561  res = hwm->send(cmdFWB);
562  i += packet_size;
563  }
564 
565  if (callback)
566  callback->on_update_progress(continue_from + (float)sector_index / (float)sector_count * ratio);
567  }
568  }
569 
570  void l500_device::update_section(std::shared_ptr<hw_monitor> hwm, const std::vector<uint8_t>& merged_image, flash_section fs, uint32_t tables_size,
571  update_progress_callback_ptr callback, float continue_from, float ratio)
572  {
573  auto first_table_offset = fs.tables.front().offset;
574  float total_size = float(fs.app_size + tables_size);
575 
576  float app_ratio = fs.app_size / total_size * ratio;
577  float tables_ratio = tables_size / total_size * ratio;
578 
579  update_flash_section(hwm, merged_image, fs.offset, fs.app_size, callback, continue_from, app_ratio);
580  update_flash_section(hwm, merged_image, first_table_offset, tables_size, callback, app_ratio, tables_ratio);
581  }
582 
583  void l500_device::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)
584  {
585  auto flash_image_info = ivcam2::get_flash_info(image);
586  auto flash_backup_info = ivcam2::get_flash_info(flash_backup);
587  auto merged_image = merge_images(flash_backup_info, flash_image_info, image);
588 
589  // update read-write section
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;
592  update_section(hwm, merged_image, flash_image_info.read_write_section, tables_size, callback, 0, update_mode == RS2_UNSIGNED_UPDATE_MODE_READ_ONLY ? 0.5f : 1.f);
593 
594  if (update_mode == RS2_UNSIGNED_UPDATE_MODE_READ_ONLY)
595  {
596  // update read-only section
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);
600  }
601  }
602 
603  void l500_device::update_flash(const std::vector<uint8_t>& image, update_progress_callback_ptr callback, int update_mode)
604  {
605  if (_is_locked)
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)");
607 
609  {
610  command cmdPFD(ivcam2::PFD);
611  cmdPFD.require_response = false;
612  auto res = _hw_monitor->send(cmdPFD);
613 
614  switch (update_mode)
615  {
617  update_flash_section(_hw_monitor, image, 0, ivcam2::FLASH_SIZE, callback, 0, 1.0);
618  break;
621  {
622  auto flash_backup = backup_flash(nullptr);
623  update_flash_internal(_hw_monitor, image, flash_backup, callback, update_mode);
624  break;
625  }
626  default:
627  throw std::runtime_error("invalid update mode value");
628  }
629 
630  if (callback) callback->on_update_progress(1.0);
631 
632  command cmdHWRST(ivcam2::HW_RESET);
633  res = _hw_monitor->send(cmdHWRST);
634  });
635  }
636 
638  {
639  return command{ ivcam2::GLD, 0x1f4 };
640  }
641 
643  {
644  return command{ ivcam2::FRB, 0x0011E000, 0x3f8 };
645  }
646 
647  static void log_FW_response_first_byte(hw_monitor& hwm, const std::string& command_name, const command &cmd, size_t expected_size)
648  {
649  auto res = hwm.send(cmd);
650  if (res.size() < expected_size)
651  {
653  << command_name + " FW command failed: size expected: "
654  << expected_size << " , size received: " << res.size());
655  }
656 
657  LOG_INFO(command_name << ": " << static_cast<int>(res[0]));
658  }
659 
660  std::vector< uint8_t > l500_device::send_receive_raw_data(const std::vector< uint8_t > & input)
661  {
662  std::string command_str(input.begin(), input.end());
663 
664  if (command_str == "GET-NEST")
665  {
666  auto minimal_fw_ver = firmware_version("1.5.0.0");
667  if (_fw_version >= minimal_fw_ver)
668  {
669  // Handle extended temperature command
670  LOG_INFO("Nest AVG: " << get_temperatures().nest_avg);
671 
672  // Handle other commands (all results log the first byte)
674  command(ivcam2::IRB, 0x6C, 0x2, 0x1),
675  sizeof(uint8_t));
677  command(ivcam2::MRD, 0xA003007C, 0xA0030080),
678  sizeof(uint32_t));
680  command(ivcam2::AMCGET, 0x4, 0x0, 0x0),
681  sizeof(uint32_t));
682  return std::vector< uint8_t >();
683  }
684  else
686  to_string() << "get-nest command requires FW version >= " << minimal_fw_ver
687  << ", current version is: " << _fw_version );
688  }
689 
690  return _hw_monitor->send(input);
691  }
692 
693 
695  {
697  if (_have_temperatures)
698  {
699  std::lock_guard<std::mutex> lock(_temperature_mutex);
700  rv = _temperatures;
701  }
702  else
703  {
704  // Noise estimation was added at FW version 1.5.0.0
705  auto fw_version_support_nest = (_fw_version >= firmware_version("1.5.0.0")) ? true : false;
706  auto expected_size = fw_version_support_nest ? sizeof(extended_temperatures)
707  : sizeof(temperatures);
708 
709 
710  const auto res = _hw_monitor->send(command{ TEMPERATURES_GET });
711  // Verify read
712  if (res.size() < expected_size)
713  {
714  throw std::runtime_error(
715  to_string() << "TEMPERATURES_GET - Invalid result size! expected: "
716  << expected_size << " bytes, "
717  "got: " << res.size() << " bytes");
718  }
719 
720  if (fw_version_support_nest)
721  rv = *reinterpret_cast<extended_temperatures const *>(res.data());
722  else
723  *reinterpret_cast<temperatures *>(&rv) = *reinterpret_cast<temperatures const *>(res.data());
724  }
725  return rv;
726  }
727 
729  {
730  LOG_DEBUG("Starting temperature fetcher thread");
732  _temperature_reader = std::thread( [&]() {
733  try
734  {
735  auto fw_version_support_nest = _fw_version >= firmware_version( "1.5.0.0" );
736 
737  auto expected_size = fw_version_support_nest ? sizeof( extended_temperatures )
738  : sizeof( temperatures );
739 
740  utilities::time::periodic_timer second_has_passed(std::chrono::seconds(1));
741  second_has_passed.set_expired(); // Force condition true on start
742 
743 
745  {
746  if (second_has_passed) // Update temperatures every second
747  {
748  const auto res = _hw_monitor->send(command{ TEMPERATURES_GET });
749  // Verify read
750  if (res.size() < expected_size)
751  {
752  throw std::runtime_error(
753  to_string() << "TEMPERATURES_GET - Invalid result size!, expected: "
754  << expected_size << " bytes, "
755  "got: " << res.size() << " bytes");
756  }
757 
758  std::lock_guard<std::mutex> lock(_temperature_mutex);
759 
760  memset(&_temperatures, sizeof(_temperatures), 0);
761  if (fw_version_support_nest)
762  _temperatures = *reinterpret_cast<extended_temperatures const *>(res.data());
763  else
764  *reinterpret_cast<temperatures *>(&_temperatures) = *reinterpret_cast<temperatures const *>(res.data());
765 
766  _have_temperatures = true;
767  }
768 
769  // Do not hold the device alive too long if reader thread was turned off
770  std::this_thread::sleep_for(std::chrono::milliseconds(300));
771  }
772  }
773  catch (...)
774  {
775  LOG_WARNING("unable to read temperatures - closing temperatures reader");
776  }
777  _have_temperatures = false;
778  });
779  }
780 
782  {
784  {
785  LOG_DEBUG("Stopping temperature fetcher thread");
787  _have_temperatures = false;
788  }
789 
790  if (_temperature_reader.joinable())
791  {
792  _temperature_reader.join();
793  }
794  }
795 
797  {
798  // Anything listed in l500-private.h on l500_fw_error_report is an error; everything else is a warning
799  if (l500_fw_error_report.find(static_cast<uint8_t>(value)) != l500_fw_error_report.end())
801 
802  return{ RS2_NOTIFICATION_CATEGORY_HARDWARE_ERROR, value, RS2_LOG_SEVERITY_WARN, (to_string() << "L500 HW report - unresolved type " << value) };
803  }
804 }
std::shared_ptr< hw_monitor > _hw_monitor
Definition: l500-device.h:91
static const textual_icon lock
Definition: model-views.h:218
virtual void register_option(rs2_option id, std::shared_ptr< option > option)
Definition: sensor.cpp:1070
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
Definition: src/types.h:92
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
Definition: l500-private.h:250
ivcam2::extended_temperatures _temperatures
Definition: l500-device.h:120
rs2_calibration_type
Definition: rs_device.h:344
auto invoke_powered(T action) -> decltype(action(*static_cast< platform::uvc_device * >(nullptr)))
Definition: sensor.h:343
filtering_processing_block(rs2_stream stream_to_pass)
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)
Definition: sensor.cpp:1567
unsigned char weeks_since_calibration
Definition: rs_types.h:88
#define LOG_WARNING(...)
Definition: src/types.h:241
double dt
Definition: boing.c:106
Video DSM (Digital Sync Module) parameters for calibration (same layout as in FW ac_depth_params) Thi...
Definition: rs_types.h:74
std::atomic_bool _have_temperatures
Definition: l500-device.h:118
virtual l500_color_sensor * get_color_sensor()=0
GLfloat value
stream_profile get_profile() const
Definition: rs_frame.hpp:557
void enter_update_state() const override
void enable_recording(std::function< void(const debug_interface &)> record_action) override
const uint32_t FLASH_SIZE
Definition: l500-private.h:34
double get_device_time_ms() override
utilities::time::work_week get_manufacture_work_week(const std::string &serial)
Definition: get-mfr-ww.cpp:17
static const std::map< usb_spec, std::string > usb_spec_names
Definition: usb-types.h:124
GLsizei const GLchar *const * string
platform::usb_spec _usb_mode
Definition: l500-device.h:114
filtering_processing_block(std::initializer_list< rs2_stream > const &streams)
unsigned char uint8_t
Definition: stdint.h:78
e
Definition: rmse.py:177
resolution l500_confidence_resolution(resolution res)
Definition: image.cpp:65
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
Definition: l500-device.h:102
GLuint index
std::shared_ptr< rs2_update_progress_callback > update_progress_callback_ptr
Definition: src/types.h:1077
GLenum GLuint GLenum GLsizei const GLchar * buf
def info(name, value, persistent=False)
Definition: test.py:301
std::shared_ptr< time_diff_keeper > _tf_keeper
GLdouble f
firmware_version _fw_version
Definition: l500-device.h:97
std::string hexify(const T &val)
Definition: src/types.h:185
bool should_process(const rs2::frame &f) override
void register_info(rs2_camera_info info, const std::string &val)
Definition: sensor.cpp:602
dictionary streams
Definition: t265_stereo.py:140
GLsizeiptr size
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
Definition: rs_device.h:206
const uint32_t FLASH_SECTOR_SIZE
Definition: l500-private.h:35
rs2_calibration_status
Definition: rs_device.h:356
std::vector< uint8_t > send(std::vector< uint8_t > const &data) const
Definition: hw-monitor.cpp:115
unsigned int uint32_t
Definition: stdint.h:80
const std::map< uint8_t, std::string > l500_fw_error_report
Definition: l500-private.h:291
GLboolean GLuint group
Definition: glext.h:5688
GLdouble GLdouble x2
l500_depth_sensor & get_depth_sensor()
uint32_t rs_fourcc(const T a, const T b, const T c, const T d)
Definition: src/types.h:1846
#define RS2_UNSIGNED_UPDATE_MODE_READ_ONLY
Definition: rs_device.h:207
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
Definition: hw-monitor.h:240
def find(dir, mask)
Definition: file.py:25
def callback(frame)
Definition: t265_stereo.py:91
virtual void configure_depth_options()
GLuint GLfloat x0
Definition: glext.h:9721
GLint j
std::map< uint32_t, rs2_format > l500_depth_fourcc_to_rs2_format
Definition: l500-device.cpp:36
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
Definition: l500-device.cpp:44
#define L5XX_RECOMMENDED_FIRMWARE_VERSION
uvc_sensor & get_raw_depth_sensor()
Definition: l500-device.h:46
unsigned get_work_weeks_since(const work_week &start)
Definition: work_week.cpp:93
#define LOG_ERROR(...)
Definition: src/types.h:242
const uint8_t L500_HWMONITOR
Definition: l500-private.h:30
rs2::frame prepare_output(const rs2::frame_source &source, rs2::frame input, std::vector< rs2::frame > results) override
const platform::extension_unit depth_xu
Definition: ds5-private.h:159
const std::string & get_info(rs2_camera_info info) const override
Definition: sensor.cpp:621
resolution rotate_resolution(resolution res)
Definition: image.cpp:60
rs2_stream
Streams are different types of data provided by RealSense devices.
Definition: rs_sensor.h:42
int add_sensor(const std::shared_ptr< sensor_interface > &sensor_base)
Definition: device.cpp:163
#define AC_LOG(TYPE, MSG)
unsigned char ac_weeks_since_calibaration
Definition: rs_types.h:89
#define RS2_UNSIGNED_UPDATE_MODE_FULL
Definition: rs_device.h:208
command get_firmware_logs_command() const
sensor_interface & get_sensor(size_t subdevice) override
Definition: device.cpp:187
std::vector< uint8_t > send_receive_raw_data(const std::vector< uint8_t > &input) override
LOG_INFO("Log message using LOG_INFO()")
GLuint GLfloat GLfloat GLfloat x1
Definition: glext.h:9721
const uint16_t HW_MONITOR_COMMAND_SIZE
Definition: hw-monitor.h:40
std::shared_ptr< context > get_context() const override
Definition: device.h:58
void override_dsm_params(rs2_dsm_params const &dsm_params) override
Definition: l500-depth.cpp:320
static auto it
GLenum GLenum GLenum input
Definition: glext.h:10805
GLenum type
std::vector< usb_device_info > usb_devices
Definition: backend.h:526
int min(int a, int b)
Definition: lz4s.c:73
std::thread _temperature_reader
Definition: l500-device.h:119
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
Definition: l500-device.h:113
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
Definition: l500-private.h:46
int i
GLuint res
Definition: glext.h:8856
#define INFO(msg)
Definition: catch.hpp:17429
void create_snapshot(std::shared_ptr< debug_interface > &snapshot) const override
#define LOG_DEBUG(...)
Definition: src/types.h:239
std::vector< platform::uvc_device_info > filter_by_mi(const std::vector< platform::uvc_device_info > &devices, uint32_t mi)
Definition: context.cpp:644
std::vector< uvc_device_info > uvc_devices
Definition: backend.h:525
const uint16_t HW_MONITOR_BUFFER_SIZE
Definition: hw-monitor.h:41
void force_hardware_reset() const
rs2_stream stream_type() const
Definition: rs_frame.hpp:39
l500_device(std::shared_ptr< context > ctx, const platform::backend_device_group &group)
Definition: l500-device.cpp:54
virtual void stop_activity() const
Definition: device.cpp:329
std::atomic_bool _keep_reading_temperature
Definition: l500-device.h:117
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
GLintptr offset
T as() const
Definition: rs_frame.hpp:580
std::string to_string(T value)


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:21