device.cpp
Go to the documentation of this file.
00001 // License: Apache 2.0. See LICENSE file in root directory.
00002 // Copyright(c) 2015 Intel Corporation. All Rights Reserved.
00003 
00004 #include "device.h"
00005 #include "sync.h"
00006 #include "motion-module.h"
00007 #include "hw-monitor.h"
00008 #include "image.h"
00009 
00010 #include <array>
00011 #include <algorithm>
00012 #include <sstream>
00013 #include <iostream>
00014 #include <functional>
00015 
00016 using namespace rsimpl;
00017 using namespace rsimpl::motion_module;
00018 
00019 const int NUMBER_OF_FRAMES_TO_SAMPLE = 5;
00020 
00021 rs_device_base::rs_device_base(std::shared_ptr<rsimpl::uvc::device> device, const rsimpl::static_device_info & info, calibration_validator validator) : device(device), config(info),
00022     depth(config, RS_STREAM_DEPTH, validator), color(config, RS_STREAM_COLOR, validator), infrared(config, RS_STREAM_INFRARED, validator), infrared2(config, RS_STREAM_INFRARED2, validator), fisheye(config, RS_STREAM_FISHEYE, validator),
00023     points(depth), rect_color(color), color_to_depth(color, depth), depth_to_color(depth, color), depth_to_rect_color(depth, rect_color), infrared2_to_depth(infrared2,depth), depth_to_infrared2(depth,infrared2),
00024     capturing(false), data_acquisition_active(false), max_publish_list_size(RS_USER_QUEUE_SIZE), event_queue_size(RS_MAX_EVENT_QUEUE_SIZE), events_timeout(RS_MAX_EVENT_TIME_OUT),
00025     usb_port_id(""), motion_module_ready(false), keep_fw_logger_alive(false), frames_drops_counter(0)
00026 {
00027     streams[RS_STREAM_DEPTH    ] = native_streams[RS_STREAM_DEPTH]     = &depth;
00028     streams[RS_STREAM_COLOR    ] = native_streams[RS_STREAM_COLOR]     = &color;
00029     streams[RS_STREAM_INFRARED ] = native_streams[RS_STREAM_INFRARED]  = &infrared;
00030     streams[RS_STREAM_INFRARED2] = native_streams[RS_STREAM_INFRARED2] = &infrared2;
00031     streams[RS_STREAM_FISHEYE  ] = native_streams[RS_STREAM_FISHEYE]   = &fisheye;
00032     streams[RS_STREAM_POINTS]                                          = &points;
00033     streams[RS_STREAM_RECTIFIED_COLOR]                                 = &rect_color;
00034     streams[RS_STREAM_COLOR_ALIGNED_TO_DEPTH]                          = &color_to_depth;
00035     streams[RS_STREAM_DEPTH_ALIGNED_TO_COLOR]                          = &depth_to_color;
00036     streams[RS_STREAM_DEPTH_ALIGNED_TO_RECTIFIED_COLOR]                = &depth_to_rect_color;
00037     streams[RS_STREAM_INFRARED2_ALIGNED_TO_DEPTH]                      = &infrared2_to_depth;
00038     streams[RS_STREAM_DEPTH_ALIGNED_TO_INFRARED2]                      = &depth_to_infrared2;
00039 }
00040 
00041 rs_device_base::~rs_device_base()
00042 {
00043     try
00044     {
00045         if (capturing) 
00046             stop(RS_SOURCE_VIDEO);
00047         if (data_acquisition_active)
00048             stop(RS_SOURCE_MOTION_TRACKING);
00049         if (keep_fw_logger_alive)
00050             stop_fw_logger();
00051     }
00052     catch (...) {}
00053 }
00054 
00055 bool rs_device_base::supports_option(rs_option option) const 
00056 { 
00057     if(uvc::is_pu_control(option)) return true;
00058     for(auto & o : config.info.options) if(o.option == option) return true;
00059     return false; 
00060 }
00061 
00062 const char* rs_device_base::get_camera_info(rs_camera_info info) const
00063 { 
00064     auto it = config.info.camera_info.find(info);
00065     if (it == config.info.camera_info.end())
00066         throw std::runtime_error("selected camera info is not supported for this camera!"); 
00067     return it->second.c_str();
00068 }
00069 
00070 void rs_device_base::enable_stream(rs_stream stream, int width, int height, rs_format format, int fps, rs_output_buffer_format output)
00071 {
00072     if(capturing) throw std::runtime_error("streams cannot be reconfigured after having called rs_start_device()");
00073     if(config.info.stream_subdevices[stream] == -1) throw std::runtime_error("unsupported stream");
00074 
00075     config.requests[stream] = { true, width, height, format, fps, output };
00076     for(auto & s : native_streams) s->archive.reset(); // Changing stream configuration invalidates the current stream info
00077 }
00078 
00079 void rs_device_base::enable_stream_preset(rs_stream stream, rs_preset preset)
00080 {
00081     if(capturing) throw std::runtime_error("streams cannot be reconfigured after having called rs_start_device()");
00082     if(!config.info.presets[stream][preset].enabled) throw std::runtime_error("unsupported stream");
00083 
00084     config.requests[stream] = config.info.presets[stream][preset];
00085     for(auto & s : native_streams) s->archive.reset(); // Changing stream configuration invalidates the current stream info
00086 }
00087 
00088 rs_motion_intrinsics rs_device_base::get_motion_intrinsics() const
00089 {
00090     throw std::runtime_error("Motion intrinsic is not supported for this device");
00091 }
00092 
00093 rs_extrinsics rs_device_base::get_motion_extrinsics_from(rs_stream /*from*/) const
00094 {
00095     throw std::runtime_error("Motion extrinsics does not supported");
00096 }
00097 
00098 void rs_device_base::disable_stream(rs_stream stream)
00099 {
00100     if(capturing) throw std::runtime_error("streams cannot be reconfigured after having called rs_start_device()");
00101     if(config.info.stream_subdevices[stream] == -1) throw std::runtime_error("unsupported stream");
00102 
00103     config.callbacks[stream] = {};
00104     config.requests[stream] = {};
00105     for(auto & s : native_streams) s->archive.reset(); // Changing stream configuration invalidates the current stream info
00106 }
00107 
00108 void rs_device_base::set_stream_callback(rs_stream stream, void (*on_frame)(rs_device * device, rs_frame_ref * frame, void * user), void * user)
00109 {
00110     config.callbacks[stream] = frame_callback_ptr(new frame_callback{ this, on_frame, user });
00111 }
00112 
00113 void rs_device_base::set_stream_callback(rs_stream stream, rs_frame_callback* callback)
00114 {
00115     config.callbacks[stream] = frame_callback_ptr(callback);
00116 }
00117 
00118 void rs_device_base::enable_motion_tracking()
00119 {
00120     if (data_acquisition_active) throw std::runtime_error("motion-tracking cannot be reconfigured after having called rs_start_device()");
00121 
00122     config.data_request.enabled = true;
00123 }
00124 
00125 void rs_device_base::disable_motion_tracking()
00126 {
00127     if (data_acquisition_active) throw std::runtime_error("motion-tracking disabled after having called rs_start_device()");
00128 
00129     config.data_request.enabled = false;
00130 }
00131 
00132 void rs_device_base::set_motion_callback(rs_motion_callback* callback)
00133 {
00134     if (data_acquisition_active) throw std::runtime_error("cannot set motion callback when motion data is active");
00135     
00136     // replace previous, if needed
00137     config.motion_callback = motion_callback_ptr(callback, [](rs_motion_callback* c) { c->release(); });
00138 }
00139 
00140 void rs_device_base::start_motion_tracking()
00141 {
00142     if (data_acquisition_active) throw std::runtime_error("cannot restart data acquisition without stopping first");
00143 
00144     auto parser = std::make_shared<motion_module_parser>();
00145 
00146     // Activate data polling handler
00147     if (config.data_request.enabled)
00148     {
00149         // TODO -replace hard-coded value 3 which stands for fisheye subdevice   
00150         set_subdevice_data_channel_handler(*device, 3,
00151             [this, parser](const unsigned char * data, const int size) mutable
00152         {
00153             if (motion_module_ready)    //  Flush all received data before MM is fully operational 
00154             {
00155                 // Parse motion data
00156                 auto events = (*parser)(data, size);
00157 
00158                 // Handle events by user-provided handlers
00159                 for (auto & entry : events)
00160                 {
00161                     // Handle Motion data packets
00162                     if (config.motion_callback)
00163                         for (int i = 0; i < entry.imu_entries_num; i++)
00164                             config.motion_callback->on_event(entry.imu_packets[i]);
00165 
00166                     // Handle Timestamp packets
00167                     if (config.timestamp_callback)
00168                     {
00169                         for (int i = 0; i < entry.non_imu_entries_num; i++)
00170                         {
00171                             auto tse = entry.non_imu_packets[i];
00172                             if (archive)
00173                                 archive->on_timestamp(tse);
00174 
00175                             config.timestamp_callback->on_event(entry.non_imu_packets[i]);
00176                         }
00177                     }
00178                 }
00179             }
00180         });
00181     }
00182 
00183     start_data_acquisition(*device);     // activate polling thread in the backend
00184     data_acquisition_active = true;
00185 }
00186 
00187 void rs_device_base::stop_motion_tracking()
00188 {
00189     if (!data_acquisition_active) throw std::runtime_error("cannot stop data acquisition - is already stopped");
00190     stop_data_acquisition(*device);
00191     data_acquisition_active = false;
00192 }
00193 
00194 void rs_device_base::set_motion_callback(void(*on_event)(rs_device * device, rs_motion_data data, void * user), void * user)
00195 {
00196     if (data_acquisition_active) throw std::runtime_error("cannot set motion callback when motion data is active");
00197     
00198     // replace previous, if needed
00199     config.motion_callback = motion_callback_ptr(new motion_events_callback(this, on_event, user), [](rs_motion_callback* c) { delete c; });
00200 }
00201 
00202 void rs_device_base::set_timestamp_callback(void(*on_event)(rs_device * device, rs_timestamp_data data, void * user), void * user)
00203 {
00204     if (data_acquisition_active) throw std::runtime_error("cannot set timestamp callback when motion data is active");
00205 
00206     config.timestamp_callback = timestamp_callback_ptr(new timestamp_events_callback{ this, on_event, user }, [](rs_timestamp_callback* c) { delete c; });
00207 }
00208 
00209 void rs_device_base::set_timestamp_callback(rs_timestamp_callback* callback)
00210 {
00211     // replace previous, if needed
00212     config.timestamp_callback = timestamp_callback_ptr(callback, [](rs_timestamp_callback* c) { c->release(); });
00213 }
00214 
00215 void rs_device_base::start(rs_source source)
00216 {
00217     if (source == RS_SOURCE_MOTION_TRACKING)
00218     {
00219         if (supports(RS_CAPABILITIES_MOTION_EVENTS))
00220             start_motion_tracking();
00221         else
00222             throw std::runtime_error("motion-tracking is not supported by this device");
00223     }
00224     else if (source == RS_SOURCE_VIDEO)
00225     {
00226         start_video_streaming();
00227     }
00228     else if (source == RS_SOURCE_ALL)
00229     {
00230         start(RS_SOURCE_MOTION_TRACKING);
00231         start(RS_SOURCE_VIDEO);
00232     }
00233     else
00234     {
00235         throw std::runtime_error("unsupported streaming source!");
00236     }
00237 }
00238 
00239 void rs_device_base::stop(rs_source source)
00240 {
00241     if (source == RS_SOURCE_VIDEO)
00242     {
00243         stop_video_streaming();
00244     }
00245     else if (source == RS_SOURCE_MOTION_TRACKING)
00246     {
00247         if (supports(RS_CAPABILITIES_MOTION_EVENTS))
00248             stop_motion_tracking();
00249         else
00250             throw std::runtime_error("motion-tracking is not supported by this device");
00251     }
00252     else if (source == RS_SOURCE_ALL)
00253     {
00254         stop(RS_SOURCE_VIDEO);
00255         stop(RS_SOURCE_MOTION_TRACKING);
00256     }
00257     else
00258     {
00259         throw std::runtime_error("unsupported streaming source");
00260     }
00261 }
00262 
00263 std::string hexify(unsigned char n)
00264 {
00265     std::string res;
00266 
00267     do
00268     {
00269         res += "0123456789ABCDEF"[n % 16];
00270         n >>= 4;
00271     } while (n);
00272 
00273     reverse(res.begin(), res.end());
00274 
00275     if (res.size() == 1)
00276     {
00277         res.insert(0, "0");
00278     }
00279 
00280     return res;
00281 }
00282 
00283 void rs_device_base::start_fw_logger(char fw_log_op_code, int grab_rate_in_ms, std::timed_mutex& mutex)
00284 {
00285     if (keep_fw_logger_alive)
00286         throw std::logic_error("FW logger already started");
00287 
00288     keep_fw_logger_alive = true;
00289     fw_logger = std::make_shared<std::thread>([this, fw_log_op_code, grab_rate_in_ms, &mutex]() {
00290         const int data_size = 500;
00291         hw_monitor::hwmon_cmd cmd((int)fw_log_op_code);
00292         cmd.Param1 = data_size;
00293         while (keep_fw_logger_alive)
00294         {
00295             std::this_thread::sleep_for(std::chrono::milliseconds(grab_rate_in_ms));
00296             hw_monitor::perform_and_send_monitor_command(this->get_device(), mutex, cmd);
00297             char data[data_size];
00298             memcpy(data, cmd.receivedCommandData, cmd.receivedCommandDataLength);
00299 
00300             std::stringstream sstr;
00301             sstr << "FW_Log_Data:";
00302             for (size_t i = 0; i < cmd.receivedCommandDataLength; ++i)
00303                 sstr << hexify(data[i]) << " ";
00304 
00305             if (cmd.receivedCommandDataLength)
00306                LOG_INFO(sstr.str());
00307         }
00308     });
00309 }
00310 
00311 void rs_device_base::stop_fw_logger()
00312 {
00313     if (!keep_fw_logger_alive)
00314         throw std::logic_error("FW logger not started");
00315 
00316     keep_fw_logger_alive = false;
00317     fw_logger->join();
00318 }
00319 
00320 struct drops_status
00321 {
00322     bool was_initialized = false;
00323     unsigned long long prev_frame_counter = 0;
00324 };
00325 
00326 void rs_device_base::start_video_streaming()
00327 {
00328     if(capturing) throw std::runtime_error("cannot restart device without first stopping device");
00329 
00330     auto capture_start_time = std::chrono::high_resolution_clock::now();
00331     auto selected_modes = config.select_modes();
00332     auto archive = std::make_shared<syncronizing_archive>(selected_modes, select_key_stream(selected_modes), &max_publish_list_size, &event_queue_size, &events_timeout, capture_start_time);
00333 
00334     for(auto & s : native_streams) s->archive.reset(); // Starting capture invalidates the current stream info, if any exists from previous capture
00335 
00336     auto timestamp_readers = create_frame_timestamp_readers();
00337 
00338     // Satisfy stream_requests as necessary for each subdevice, calling set_mode and
00339     // dispatching the uvc configuration for a requested stream to the hardware
00340     for(auto mode_selection : selected_modes)
00341     {
00342         assert(static_cast<size_t>(mode_selection.mode.subdevice) <= timestamp_readers.size());
00343         auto timestamp_reader = timestamp_readers[mode_selection.mode.subdevice];
00344 
00345         // Create a stream buffer for each stream served by this subdevice mode
00346         for(auto & stream_mode : mode_selection.get_outputs())
00347         {                    
00348             // If this is one of the streams requested by the user, store the buffer so they can access it
00349             if(config.requests[stream_mode.first].enabled) native_streams[stream_mode.first]->archive = archive;
00350         }
00351 
00352         // Copy the callbacks that apply to this stream, so that they can be captured by value
00353         std::vector<rs_stream> streams;
00354         for (auto & output : mode_selection.get_outputs())
00355         {
00356             streams.push_back(output.first);
00357         }     
00358 
00359         auto supported_metadata_vector = std::make_shared<std::vector<rs_frame_metadata>>(config.info.supported_metadata_vector);
00360 
00361         auto actual_fps_calc = std::make_shared<fps_calc>(NUMBER_OF_FRAMES_TO_SAMPLE, mode_selection.get_framerate());
00362         std::shared_ptr<drops_status> frame_drops_status(new drops_status{});
00363         // Initialize the subdevice and set it to the selected mode
00364         set_subdevice_mode(*device, mode_selection.mode.subdevice, mode_selection.mode.native_dims.x, mode_selection.mode.native_dims.y, mode_selection.mode.pf.fourcc, mode_selection.mode.fps, 
00365             [this, mode_selection, archive, timestamp_reader, streams, capture_start_time, frame_drops_status, actual_fps_calc, supported_metadata_vector](const void * frame, std::function<void()> continuation) mutable
00366         {
00367             auto now = std::chrono::system_clock::now();
00368             auto sys_time = std::chrono::duration_cast<std::chrono::milliseconds>(now.time_since_epoch()).count();
00369 
00370             frame_continuation release_and_enqueue(continuation, frame);
00371 
00372             // Ignore any frames which appear corrupted or invalid
00373             if (!timestamp_reader->validate_frame(mode_selection.mode, frame)) return;
00374             
00375             auto actual_fps = actual_fps_calc->calc_fps(now);
00376 
00377             // Determine the timestamp for this frame
00378             auto timestamp = timestamp_reader->get_frame_timestamp(mode_selection.mode, frame, actual_fps);
00379             auto frame_counter = timestamp_reader->get_frame_counter(mode_selection.mode, frame);
00380             auto recieved_time = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::high_resolution_clock::now() - capture_start_time).count();
00381 
00382             auto requires_processing = mode_selection.requires_processing();
00383 
00384             double exposure_value[1] = {};
00385             if (streams[0] == rs_stream::RS_STREAM_FISHEYE)
00386             {
00387                 // fisheye exposure value is embedded in the frame data from version 1.27.2.90
00388                 firmware_version firmware(get_camera_info(RS_CAMERA_INFO_ADAPTER_BOARD_FIRMWARE_VERSION));
00389                 if (firmware >= firmware_version("1.27.2.90"))
00390                 {
00391                     auto data = static_cast<const char*>(frame);
00392                     int exposure = 0; // Embedded Fisheye exposure value is in units of 0.2 mSec
00393                     for (int i = 4, j = 0; i < 12; ++i, ++j)
00394                         exposure |= ((data[i] & 0x01) << j);
00395 
00396                     exposure_value[0] = exposure * 0.2 * 10.;
00397                 }
00398             }
00399 
00400             auto width = mode_selection.get_width();
00401             auto height = mode_selection.get_height();
00402             auto fps = mode_selection.get_framerate();
00403             std::vector<byte *> dest;
00404 
00405             auto stride_x = mode_selection.get_stride_x();
00406             auto stride_y = mode_selection.get_stride_y();
00407             for (auto & output : mode_selection.get_outputs())
00408             {
00409                 LOG_DEBUG("FrameAccepted, RecievedAt," << recieved_time << ", FWTS," << timestamp << ", DLLTS," << recieved_time << ", Type," << rsimpl::get_string(output.first) << ",HasPair,0,F#," << frame_counter);
00410             }
00411             
00412             frame_drops_status->was_initialized = true;
00413 
00414             // Not updating prev_frame_counter when first frame arrival
00415             if (frame_drops_status->was_initialized)
00416             {
00417                 frames_drops_counter.fetch_add(frame_counter - frame_drops_status->prev_frame_counter - 1);
00418                 frame_drops_status->prev_frame_counter = frame_counter;
00419             }
00420 
00421             for (auto & output : mode_selection.get_outputs())
00422             {
00423                 auto bpp = get_image_bpp(output.second);
00424                 frame_archive::frame_additional_data additional_data( timestamp,
00425                     frame_counter,
00426                     sys_time,
00427                     width,
00428                     height,
00429                     fps,
00430                     stride_x,
00431                     stride_y,
00432                     bpp,
00433                     output.second,
00434                     output.first,
00435                     mode_selection.pad_crop,
00436                     supported_metadata_vector,
00437                     exposure_value[0],
00438                     actual_fps);
00439 
00440                 // Obtain buffers for unpacking the frame
00441                 dest.push_back(archive->alloc_frame(output.first, additional_data, requires_processing));
00442 
00443 
00444                 if (motion_module_ready) // try to correct timestamp only if motion module is enabled
00445                 {
00446                     archive->correct_timestamp(output.first);
00447                 }
00448             }
00449             // Unpack the frame
00450             if (requires_processing)
00451             {
00452                 mode_selection.unpack(dest.data(), reinterpret_cast<const byte *>(frame));
00453             }
00454 
00455             // If any frame callbacks were specified, dispatch them now
00456             for (size_t i = 0; i < dest.size(); ++i)
00457             {
00458                 if (!requires_processing)
00459                 {
00460                     archive->attach_continuation(streams[i], std::move(release_and_enqueue));
00461                 }
00462 
00463                 if (config.callbacks[streams[i]])
00464                 {
00465                     auto frame_ref = archive->track_frame(streams[i]);
00466                     if (frame_ref)
00467                     {
00468                         frame_ref->update_frame_callback_start_ts(std::chrono::high_resolution_clock::now());
00469                         frame_ref->log_callback_start(capture_start_time);
00470                         on_before_callback(streams[i], frame_ref, archive);
00471                         (*config.callbacks[streams[i]])->on_frame(this, frame_ref);
00472                     }
00473                 }
00474                 else
00475                 {
00476                     // Commit the frame to the archive
00477                     archive->commit_frame(streams[i]);
00478                 }
00479             }
00480         });
00481     }
00482     
00483     this->archive = archive;
00484     on_before_start(selected_modes);
00485     start_streaming(*device, config.info.num_libuvc_transfer_buffers);
00486     capture_started = std::chrono::high_resolution_clock::now();
00487     capturing = true;
00488 }
00489 
00490 void rs_device_base::stop_video_streaming()
00491 {
00492     if(!capturing) throw std::runtime_error("cannot stop device without first starting device");
00493     stop_streaming(*device);
00494     archive->flush();
00495     capturing = false;
00496 }
00497 
00498 void rs_device_base::wait_all_streams()
00499 {
00500     if(!capturing) return;
00501     if(!archive) return;
00502 
00503     archive->wait_for_frames();
00504 }
00505 
00506 bool rs_device_base::poll_all_streams()
00507 {
00508     if(!capturing) return false;
00509     if(!archive) return false;
00510     return archive->poll_for_frames();
00511 }
00512 
00513 void rs_device_base::release_frame(rs_frame_ref* ref)
00514 {
00515     archive->release_frame_ref((frame_archive::frame_ref *)ref);
00516 }
00517 
00518 rs_frame_ref* ::rs_device_base::clone_frame(rs_frame_ref* frame)
00519 {
00520     auto result = archive->clone_frame((frame_archive::frame_ref *)frame);
00521     if (!result) throw std::runtime_error("Not enough resources to clone frame!");
00522     return result;
00523 }
00524 
00525 void rs_device_base::update_device_info(rsimpl::static_device_info& info)
00526 {
00527     info.options.push_back({ RS_OPTION_FRAMES_QUEUE_SIZE,     1, RS_USER_QUEUE_SIZE,      1, RS_USER_QUEUE_SIZE });
00528 }
00529 
00530 const char * rs_device_base::get_option_description(rs_option option) const
00531 {
00532     switch (option)
00533     {
00534     case RS_OPTION_COLOR_BACKLIGHT_COMPENSATION                    : return "Enable / disable color backlight compensation";
00535     case RS_OPTION_COLOR_BRIGHTNESS                                : return "Color image brightness";
00536     case RS_OPTION_COLOR_CONTRAST                                  : return "Color image contrast";
00537     case RS_OPTION_COLOR_EXPOSURE                                  : return "Controls exposure time of color camera. Setting any value will disable auto exposure";
00538     case RS_OPTION_COLOR_GAIN                                      : return "Color image gain";
00539     case RS_OPTION_COLOR_GAMMA                                     : return "Color image gamma setting";
00540     case RS_OPTION_COLOR_HUE                                       : return "Color image hue";
00541     case RS_OPTION_COLOR_SATURATION                                : return "Color image saturation setting";
00542     case RS_OPTION_COLOR_SHARPNESS                                 : return "Color image sharpness setting";
00543     case RS_OPTION_COLOR_WHITE_BALANCE                             : return "Controls white balance of color image. Setting any value will disable auto white balance";
00544     case RS_OPTION_COLOR_ENABLE_AUTO_EXPOSURE                      : return "Enable / disable color image auto-exposure";
00545     case RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE                 : return "Enable / disable color image auto-white-balance";
00546     case RS_OPTION_F200_LASER_POWER                                : return "Power of the F200 / SR300 projector, with 0 meaning projector off";
00547     case RS_OPTION_F200_ACCURACY                                   : return "Set the number of patterns projected per frame. The higher the accuracy value the more patterns projected. Increasing the number of patterns help to achieve better accuracy. Note that this control is affecting the Depth FPS";
00548     case RS_OPTION_F200_MOTION_RANGE                               : return "Motion vs. Range trade-off, with lower values allowing for better motion sensitivity and higher values allowing for better depth range";
00549     case RS_OPTION_F200_FILTER_OPTION                              : return "Set the filter to apply to each depth frame. Each one of the filter is optimized per the application requirements";
00550     case RS_OPTION_F200_CONFIDENCE_THRESHOLD                       : return "The confidence level threshold used by the Depth algorithm pipe to set whether a pixel will get a valid range or will be marked with invalid range";
00551     case RS_OPTION_F200_DYNAMIC_FPS                                : return "(F200-only) Allows to reduce FPS without restarting streaming. Valid values are {2, 5, 15, 30, 60}";
00552     case RS_OPTION_SR300_AUTO_RANGE_ENABLE_MOTION_VERSUS_RANGE     : return "Configures SR300 Depth Auto-Range setting (Should be used through set IVCAM preset method)";
00553     case RS_OPTION_SR300_AUTO_RANGE_ENABLE_LASER                   : return "Configures SR300 Depth Auto-Range Laser setting (Should be used through set IVCAM preset method)";
00554     case RS_OPTION_SR300_AUTO_RANGE_MIN_MOTION_VERSUS_RANGE        : return "Configures SR300 Depth Auto-Range Min laser motion setting (Should be used through set IVCAM preset method)";
00555     case RS_OPTION_SR300_AUTO_RANGE_MAX_MOTION_VERSUS_RANGE        : return "Configures SR300 Depth Auto-Range Max laser motion setting (Should be used through set IVCAM preset method)";
00556     case RS_OPTION_SR300_AUTO_RANGE_START_MOTION_VERSUS_RANGE      : return "Configures SR300 Depth Auto-Range start laser motion setting (Should be used through set IVCAM preset method)";
00557     case RS_OPTION_SR300_AUTO_RANGE_MIN_LASER                      : return "Configures SR300 Depth Auto-Range Min laser setting (Should be used through set IVCAM preset method)";
00558     case RS_OPTION_SR300_AUTO_RANGE_MAX_LASER                      : return "Configures SR300 Depth Auto-Range Max laser setting (Should be used through set IVCAM preset method)";
00559     case RS_OPTION_SR300_AUTO_RANGE_START_LASER                    : return "Configures SR300 Depth Auto-Range Start laser setting (Should be used through set IVCAM preset method)";
00560     case RS_OPTION_SR300_AUTO_RANGE_UPPER_THRESHOLD                : return "Configures SR300 Depth Auto-Range upper threshold setting (Should be used through set IVCAM preset method)";
00561     case RS_OPTION_SR300_AUTO_RANGE_LOWER_THRESHOLD                : return "Configures SR300 Depth Auto-Range lower threshold setting (Should be used through set IVCAM preset method)";
00562     case RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED                   : return "Enables / disables R200 auto-exposure. This will affect both IR and depth image.";
00563     case RS_OPTION_R200_LR_GAIN                                    : return "IR image gain";
00564     case RS_OPTION_R200_LR_EXPOSURE                                : return "This control allows manual adjustment of the exposure time value for the L/R imagers";
00565     case RS_OPTION_R200_EMITTER_ENABLED                            : return "Enables / disables R200 emitter";
00566     case RS_OPTION_R200_DEPTH_UNITS                                : return "Micrometers per increment in integer depth values, 1000 is default (mm scale). Set before streaming";
00567     case RS_OPTION_R200_DEPTH_CLAMP_MIN                            : return "Minimum depth in current depth units that will be output. Any values less than 'Min Depth' will be mapped to 0 during the conversion between disparity and depth. Set before streaming";
00568     case RS_OPTION_R200_DEPTH_CLAMP_MAX                            : return "Maximum depth in current depth units that will be output. Any values greater than 'Max Depth' will be mapped to 0 during the conversion between disparity and depth. Set before streaming";
00569     case RS_OPTION_R200_DISPARITY_MULTIPLIER                       : return "The disparity scale factor used when in disparity output mode. Can only be set before streaming";
00570     case RS_OPTION_R200_DISPARITY_SHIFT                            : return "{0 - 512}. Can only be set before streaming starts";
00571     case RS_OPTION_R200_AUTO_EXPOSURE_MEAN_INTENSITY_SET_POINT     : return "(Requires LR-Auto-Exposure ON) Mean intensity set point";
00572     case RS_OPTION_R200_AUTO_EXPOSURE_BRIGHT_RATIO_SET_POINT       : return "(Requires LR-Auto-Exposure ON) Bright ratio set point";
00573     case RS_OPTION_R200_AUTO_EXPOSURE_KP_GAIN                      : return "(Requires LR-Auto-Exposure ON) Kp Gain";
00574     case RS_OPTION_R200_AUTO_EXPOSURE_KP_EXPOSURE                  : return "(Requires LR-Auto-Exposure ON) Kp Exposure";
00575     case RS_OPTION_R200_AUTO_EXPOSURE_KP_DARK_THRESHOLD            : return "(Requires LR-Auto-Exposure ON) Kp Dark Threshold";
00576     case RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE                     : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest top edge (in pixels)";
00577     case RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE                  : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest bottom edge (in pixels)";
00578     case RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE                    : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest left edge (in pixels)";
00579     case RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE                   : return "(Requires LR-Auto-Exposure ON) Auto-Exposure region-of-interest right edge (in pixels)";
00580     case RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT    : return "Value to subtract when estimating the median of the correlation surface";
00581     case RS_OPTION_R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT    : return "Value to add when estimating the median of the correlation surface";
00582     case RS_OPTION_R200_DEPTH_CONTROL_MEDIAN_THRESHOLD             : return "A threshold by how much the winning score must beat the median";
00583     case RS_OPTION_R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD      : return "The minimum correlation score that is considered acceptable";
00584     case RS_OPTION_R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD      : return "The maximum correlation score that is considered acceptable";
00585     case RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD      : return "A parameter for determining whether the texture in the region is sufficient to justify a depth result";
00586     case RS_OPTION_R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD : return "A parameter for determining whether the texture in the region is sufficient to justify a depth result";
00587     case RS_OPTION_R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD        : return "A threshold on how much the minimum correlation score must differ from the next best score";
00588     case RS_OPTION_R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD           : return "Neighbor threshold value for depth calculation";
00589     case RS_OPTION_R200_DEPTH_CONTROL_LR_THRESHOLD                 : return "Left-Right threshold value for depth calculation";
00590     case RS_OPTION_FISHEYE_EXPOSURE                                : return "Fisheye image exposure time in msec";
00591     case RS_OPTION_FISHEYE_GAIN                                    : return "Fisheye image gain";
00592     case RS_OPTION_FISHEYE_STROBE                                  : return "Enables / disables fisheye strobe. When enabled this will align timestamps to common clock-domain with the motion events";
00593     case RS_OPTION_FISHEYE_EXTERNAL_TRIGGER                        : return "Enables / disables fisheye external trigger mode. When enabled fisheye image will be acquired in-sync with the depth image";
00594     case RS_OPTION_FRAMES_QUEUE_SIZE                               : return "Number of frames the user is allowed to keep per stream. Trying to hold-on to more frames will cause frame-drops.";
00595     case RS_OPTION_FISHEYE_ENABLE_AUTO_EXPOSURE                    : return "Enable / disable fisheye auto-exposure";
00596     case RS_OPTION_FISHEYE_AUTO_EXPOSURE_MODE                      : return "0 - static auto-exposure, 1 - anti-flicker auto-exposure, 2 - hybrid";
00597     case RS_OPTION_FISHEYE_AUTO_EXPOSURE_ANTIFLICKER_RATE          : return "Fisheye auto-exposure anti-flicker rate, can be 50 or 60 Hz";
00598     case RS_OPTION_FISHEYE_AUTO_EXPOSURE_PIXEL_SAMPLE_RATE         : return "In Fisheye auto-exposure sample frame every given number of pixels";
00599     case RS_OPTION_FISHEYE_AUTO_EXPOSURE_SKIP_FRAMES               : return "In Fisheye auto-exposure sample every given number of frames";
00600     case RS_OPTION_HARDWARE_LOGGER_ENABLED                         : return "Enables / disables fetching diagnostic information from hardware (and writting the results to log)";
00601     case RS_OPTION_TOTAL_FRAME_DROPS                               : return "Total number of detected frame drops from all streams";
00602     default: return rs_option_to_string(option);
00603     }
00604 }
00605 
00606 bool rs_device_base::supports(rs_capabilities capability) const
00607 {
00608     auto found = false;
00609     auto version_ok = true;
00610     for (auto supported : config.info.capabilities_vector)
00611     {
00612         if (supported.capability == capability)
00613         {
00614             found = true;
00615 
00616             firmware_version firmware(get_camera_info(supported.firmware_type));
00617             if (!firmware.is_between(supported.from, supported.until)) // unsupported due to versioning constraint
00618             {
00619                 LOG_WARNING("capability " << rs_capabilities_to_string(capability) << " requires " << rs_camera_info_to_string(supported.firmware_type) << " to be from " << supported.from << " up-to " << supported.until << ", but is " << firmware << "!");
00620                 version_ok = false;
00621             }
00622         }
00623     }
00624     return found && version_ok;
00625 }
00626 
00627 bool rs_device_base::supports(rs_camera_info info_param) const
00628 {
00629     auto it = config.info.camera_info.find(info_param);
00630     return (it != config.info.camera_info.end());
00631 }
00632 
00633 void rs_device_base::get_option_range(rs_option option, double & min, double & max, double & step, double & def)
00634 {
00635     if(uvc::is_pu_control(option))
00636     {
00637         int mn, mx, stp, df;
00638         uvc::get_pu_control_range(get_device(), config.info.stream_subdevices[RS_STREAM_COLOR], option, &mn, &mx, &stp, &df);
00639         min  = mn;
00640         max  = mx;
00641         step = stp;
00642         def  = df;
00643         return;
00644     }
00645 
00646     for(auto & o : config.info.options)
00647     {
00648         if(o.option == option)
00649         {
00650             min = o.min;
00651             max = o.max;
00652             step = o.step;
00653             def = o.def;
00654             return;
00655         }
00656     }
00657 
00658     throw std::logic_error("range not specified");
00659 }
00660 
00661 void rs_device_base::set_options(const rs_option options[], size_t count, const double values[])
00662 {
00663     for (size_t i = 0; i < count; ++i)
00664     {
00665         switch (options[i])
00666         {
00667         case  RS_OPTION_FRAMES_QUEUE_SIZE:
00668             max_publish_list_size = (uint32_t)values[i];
00669             break;
00670         case RS_OPTION_TOTAL_FRAME_DROPS:
00671             frames_drops_counter = (uint32_t)values[i];
00672             break;
00673         default:
00674             LOG_WARNING("Cannot set " << options[i] << " to " << values[i] << " on " << get_name());
00675             throw std::logic_error("Option unsupported");
00676             break;
00677         }
00678     }
00679 }
00680 
00681 void rs_device_base::get_options(const rs_option options[], size_t count, double values[])
00682 {
00683     for (size_t i = 0; i < count; ++i)
00684     {
00685         switch (options[i])
00686         {
00687         case  RS_OPTION_FRAMES_QUEUE_SIZE:
00688             values[i] = max_publish_list_size;
00689             break;
00690         case  RS_OPTION_TOTAL_FRAME_DROPS:
00691             values[i] = frames_drops_counter;
00692             break;
00693         default:
00694             LOG_WARNING("Cannot get " << options[i] << " on " << get_name());
00695             throw std::logic_error("Option unsupported");
00696             break;
00697         }
00698     }
00699 }
00700 
00701 void rs_device_base::disable_auto_option(int subdevice, rs_option auto_opt)
00702 {
00703     static const int reset_state = 0;
00704     // Probe , then deactivate
00705     if (uvc::get_pu_control(get_device(), subdevice, auto_opt))
00706         uvc::set_pu_control(get_device(), subdevice, auto_opt, reset_state);
00707 }
00708 
00709 
00710 const char * rs_device_base::get_usb_port_id() const
00711 {
00712     std::lock_guard<std::mutex> lock(usb_port_mutex);
00713     if (usb_port_id == "") usb_port_id = rsimpl::uvc::get_usb_port_id(*device);
00714     return usb_port_id.c_str();
00715 }


librealsense
Author(s): Sergey Dorodnicov , Mark Horn , Reagan Lopez
autogenerated on Tue Jun 25 2019 19:54:38