11 #include <unordered_set> 12 #include <unordered_map> 32 typedef std::function<void(std::vector<platform::stream_profile>)>
on_open;
39 virtual unsigned long long get_frame_counter(
const std::shared_ptr<frame_interface>& frame)
const = 0;
41 virtual void reset() = 0;
44 class sensor_base :
public std::enable_shared_from_this<sensor_base>,
59 int register_before_streaming_changes_callback(std::function<
void(
bool)> callback)
override;
60 void unregister_before_start_callback(
int token)
override;
61 virtual std::shared_ptr<notifications_processor> get_notifications_processor()
const;
64 bool is_streaming()
const override;
65 virtual bool is_opened()
const;
82 std::shared_ptr<std::map<uint32_t, rs2_format>>& get_fourcc_to_rs2_format_map();
83 std::shared_ptr<std::map<uint32_t, rs2_stream>>& get_fourcc_to_rs2_stream_map();
89 void raise_on_before_streaming_changes(
bool streaming);
92 void assign_stream(
const std::shared_ptr<stream_interface>&
stream,
93 std::shared_ptr<stream_profile_interface>
target)
const;
98 const unsigned long long& last_frame_number,
99 std::shared_ptr<stream_profile_interface>
profile);
107 std::shared_ptr<metadata_parser_map> _metadata_parsers =
nullptr;
131 void create_snapshot(std::shared_ptr<motion_sensor>& snapshot)
const override;
142 void update(std::shared_ptr<extension_snapshot> ext)
override 148 snapshot = std::make_shared<motion_sensor_snapshot>(*this);
163 void create_snapshot(std::shared_ptr<fisheye_sensor>& snapshot)
const override;
174 void update(std::shared_ptr<extension_snapshot> ext)
override 180 snapshot = std::make_shared<fisheye_sensor_snapshot>(*this);
193 std::shared_ptr<sensor_base>
sensor,
195 const std::map<uint32_t, rs2_format>& fourcc_to_rs2_format_map = std::map<uint32_t, rs2_format>(),
196 const std::map<uint32_t, rs2_stream>& fourcc_to_rs2_stream_map = std::map<uint32_t, rs2_stream>());
199 virtual void register_option(
rs2_option id, std::shared_ptr<option>
option);
200 virtual bool try_register_option(
rs2_option id, std::shared_ptr<option> option);
208 void close()
override;
210 void stop()
override;
212 void register_processing_block(
const std::vector<stream_profile>& from,
213 const std::vector<stream_profile>& to,
214 std::function<std::shared_ptr<processing_block>(
void)> generate_func);
216 void register_processing_block(
const std::vector<processing_block_factory>& pbfs);
222 int register_before_streaming_changes_callback(std::function<
void(
bool)> callback)
override;
223 void unregister_before_start_callback(
int token)
override;
225 bool is_streaming()
const override;
226 bool is_opened()
const override;
229 void add_source_profiles_missing_data();
233 std::shared_ptr<stream_profile_interface> filter_frame_by_requests(
const frame_interface*
f);
236 void add_source_profile_missing_data(std::shared_ptr<stream_profile_interface>& source_profile);
237 bool is_duplicated_profile(
const std::shared_ptr<stream_profile_interface>& duplicate,
const stream_profiles& profiles);
238 std::shared_ptr<stream_profile_interface> clone_profile(
const std::shared_ptr<stream_profile_interface>&
profile);
257 static const int sensors = 2;
260 mutable std::recursive_mutex
_mtx;
264 void reset()
override;
268 bool has_metadata(
const std::shared_ptr<frame_interface>&
frame)
const;
278 explicit hid_sensor(std::shared_ptr<platform::hid_device> hid_device,
279 std::unique_ptr<frame_timestamp_reader> hid_iio_timestamp_reader,
280 std::unique_ptr<frame_timestamp_reader> custom_hid_timestamp_reader,
281 const std::map<
rs2_stream, std::map<unsigned, unsigned>>& fps_and_sampling_frequency_per_rs2_stream,
282 const std::vector<std::pair<std::string, stream_profile>>& sensor_name_and_hid_profiles,
288 void close()
override;
290 void stop()
override;
292 std::vector<uint8_t> get_custom_report_data(
const std::string& custom_sensor_name,
327 std::unique_ptr<frame_timestamp_reader> timestamp_reader,
device*
dev);
331 void close()
override;
333 void stop()
override;
344 -> decltype(
action(*static_cast<platform::uvc_device*>(
nullptr)))
346 power on(std::dynamic_pointer_cast<uvc_sensor>(shared_from_this()));
355 void acquire_power();
356 void release_power();
357 void reset_streaming();
361 explicit power(std::weak_ptr<uvc_sensor> owner)
364 auto strong = _owner.lock();
367 strong->acquire_power();
373 if (
auto strong = _owner.lock())
377 strong->release_power();
386 std::shared_ptr<platform::uvc_device>
_device;
390 std::vector<platform::extension_unit>
_xus;
rs2_camera_info
Read-only strings that can be queried from the device. Not all information attributes are available o...
void enable_recording(std::function< void(const fisheye_sensor &)> recording_function) override
boost_foreach_argument_dependent_lookup_hack tag
std::string get_device_path() const
std::atomic< bool > _is_opened
GLuint const GLchar * name
auto invoke_powered(T action) -> decltype(action(*static_cast< platform::uvc_device * >(nullptr)))
rs2_option
Defines general configuration controls. These can generally be mapped to camera UVC controls...
void enable_recording(std::function< void(const fisheye_sensor &)> recording_function) override
std::function< void(std::vector< platform::stream_profile >)> on_open
std::shared_ptr< rs2_frame_callback > frame_callback_ptr
void create_snapshot(std::shared_ptr< motion_sensor > &snapshot) const override
std::shared_ptr< sensor_base > get_raw_sensor() const
std::mutex _synthetic_configure_lock
processing_blocks get_color_recommended_proccesing_blocks()
std::unordered_map< processing_block_factory *, stream_profiles > _pbf_supported_profiles
void update(std::shared_ptr< extension_snapshot > ext) override
std::vector< platform::hid_sensor > _hid_sensors
void create_snapshot(std::shared_ptr< fisheye_sensor > &snapshot) const override
std::unordered_map< stream_profile, stream_profiles > _target_to_source_profiles_map
GLsizei const GLchar *const * string
virtual ~sensor_base() override
std::shared_ptr< platform::hid_device > _hid_device
static const textual_icon stop
std::shared_ptr< platform::uvc_device > _device
frame_callback_ptr _post_process_callback
std::mutex _active_profile_mutex
std::vector< platform::extension_unit > _xus
std::vector< bool > _is_configured_stream
std::shared_ptr< sensor_base > _raw_sensor
std::shared_ptr< platform::uvc_device > get_uvc_device()
std::unique_ptr< frame_timestamp_reader > _hid_iio_timestamp_reader
std::atomic< int > _user_count
def info(name, value, persistent=False)
std::unordered_map< rs2_format, stream_profiles > _cached_requests
std::unique_ptr< power > _power
std::mutex _configure_lock
processing_blocks get_depth_recommended_proccesing_blocks()
void update(std::shared_ptr< extension_snapshot > ext) override
std::shared_ptr< std::map< uint32_t, rs2_format > > _fourcc_to_rs2_format
stream_profiles _active_profiles
std::unique_ptr< frame_timestamp_reader > _custom_hid_timestamp_reader
std::vector< rs2::stream_profile > init_stream_profiles(sw_context &sctx, std::shared_ptr< rs2::software_sensor > ss, std::string sensor_name, rs2::video_stream_profile c, rs2::video_stream_profile d)
std::shared_ptr< rs2_notifications_callback > notifications_callback_ptr
std::recursive_mutex _mtx
uint32_t rs_fourcc(const T a, const T b, const T c, const T d)
std::shared_ptr< notifications_processor > _notifications_processor
std::vector< platform::stream_profile > _uvc_profiles
GLint GLint GLsizei GLint GLenum format
const std::vector< std::pair< std::string, stream_profile > > _sensor_name_and_hid_profiles
rs2_format
A stream's format identifies how binary data is encoded within a frame.
std::vector< platform::stream_profile > _internal_config
platform::usb_spec get_usb_specification() const
virtual ~frame_timestamp_reader()
signal< sensor_base, bool > on_before_streaming_changes
std::vector< std::shared_ptr< stream_profile_interface >> stream_profiles
rs2_stream
Streams are different types of data provided by RealSense devices.
void enable_recording(std::function< void(const motion_sensor &)> recording_function) override
std::mutex _configure_lock
virtual unsigned long long get_frame_counter(const std::shared_ptr< frame_interface > &frame) const =0
std::vector< platform::stream_profile > get_configuration() const
std::vector< int64_t > counter
rs2_extension
Specifies advanced interfaces (capabilities) objects may implement.
std::unique_ptr< frame_timestamp_reader > _timestamp_reader
::realsense_legacy_msgs::metadata_< std::allocator< void > > metadata
virtual rs2_timestamp_domain get_frame_timestamp_domain(const std::shared_ptr< frame_interface > &frame) const =0
lazy< stream_profiles > _profiles
void register_on_open(on_open callback)
std::vector< std::shared_ptr< processing_block_factory > > _pb_factories
std::unordered_map< std::shared_ptr< stream_profile_interface >, std::unordered_set< std::shared_ptr< processing_block > > > _profiles_to_processing_block
power(std::weak_ptr< uvc_sensor > owner)
std::unordered_map< std::shared_ptr< stream_profile_interface >, stream_profiles > _source_to_target_profiles_map
std::vector< rs2_option > _cached_processing_blocks_options
static rs2::device get_device()
virtual double get_frame_timestamp(const std::shared_ptr< frame_interface > &frame)=0
fisheye_sensor_snapshot()
std::atomic< bool > _is_streaming
std::shared_ptr< std::map< uint32_t, rs2_stream > > _fourcc_to_rs2_stream
std::map< rs2_stream, std::map< uint32_t, uint32_t > > _fps_and_sampling_frequency_per_rs2_stream
std::map< std::string, std::shared_ptr< stream_profile_interface > > _configured_profiles
GeneratorWrapper< T > map(Func &&function, GeneratorWrapper< U > &&generator)
void enable_recording(std::function< void(const motion_sensor &)> recording_function) override
processing_blocks get_recommended_processing_blocks() const override
rs2_frame_metadata_value
Per-Frame-Metadata is the set of read-only properties that might be exposed for each individual frame...
MAP_EXTENSION(RS2_EXTENSION_POINTS, librealsense::points)
std::weak_ptr< uvc_sensor > _owner
rs2_timestamp_domain
Specifies the clock in relation to which the frame timestamp was measured.