metadata_extractor.h
Go to the documentation of this file.
1 // SPDX-License-Identifier: BSD-3-Clause
2 // SPDX-FileCopyrightText: Czech Technical University in Prague
3 
10 #pragma once
11 
12 #include <algorithm>
13 #include <memory>
14 #include <string>
15 #include <unordered_set>
16 #include <utility>
17 #include <vector>
18 
19 #include <compass_msgs/Azimuth.h>
23 #include <geometry_msgs/Transform.h>
24 #include <geometry_msgs/TransformStamped.h>
25 #include <geometry_msgs/Vector3.h>
26 #include <gps_common/GPSFix.h>
31 #include <ros/time.h>
32 #include <sensor_msgs/CameraInfo.h>
33 #include <sensor_msgs/Imu.h>
34 #include <sensor_msgs/MagneticField.h>
35 #include <sensor_msgs/NavSatFix.h>
36 #include <vision_msgs/Detection2DArray.h>
37 
38 class AVFormatContext;
39 class AVPacket;
40 
41 namespace movie_publisher
42 {
43 
44 class MetadataManager;
45 
50 {
52  std::weak_ptr<MetadataManager> manager;
55  const AVFormatContext* avFormatContext;
56  std::shared_ptr<MetadataCache> cache;
57 };
58 
77 {
78 public:
79  using Ptr = std::shared_ptr<MetadataExtractor>;
80  using ConstPtr = std::shared_ptr<const MetadataExtractor>;
81 
86  explicit MetadataExtractor(const cras::LogHelperPtr& log);
87  virtual ~MetadataExtractor();
88 
93  virtual std::string getName() const = 0;
94 
99  virtual int getPriority() const = 0;
100 
106  virtual void processPacket(const AVPacket* packet) {}
107 
111  virtual cras::optional<std::string> getCameraGeneralName() { return cras::nullopt; }
116  virtual cras::optional<std::string> getCameraUniqueName() { return cras::nullopt; }
120  virtual cras::optional<std::string> getCameraSerialNumber() { return cras::nullopt; }
124  virtual cras::optional<std::string> getCameraMake() { return cras::nullopt; }
128  virtual cras::optional<std::string> getCameraModel() { return cras::nullopt; }
132  virtual cras::optional<std::string> getLensMake() { return cras::nullopt; }
136  virtual cras::optional<std::string> getLensModel() { return cras::nullopt; }
140  virtual cras::optional<int> getRotation() { return cras::nullopt; }
144  virtual cras::optional<ros::Time> getCreationTime() { return cras::nullopt; }
148  virtual cras::optional<double> getCropFactor() { return cras::nullopt; }
152  virtual cras::optional<SensorSize> getSensorSizeMM() { return cras::nullopt; }
156  virtual cras::optional<double> getFocalLength35MM() { return cras::nullopt; }
160  virtual cras::optional<double> getFocalLengthMM() { return cras::nullopt; }
164  virtual cras::optional<double> getFocalLengthPx() { return cras::nullopt; }
168  virtual cras::optional<IntrinsicMatrix> getIntrinsicMatrix() { return cras::nullopt; }
172  virtual cras::optional<DistortionData> getDistortion() { return cras::nullopt; }
176  virtual GNSSFixAndDetail getGNSSPosition() { return std::make_pair(cras::nullopt, cras::nullopt); }
180  virtual cras::optional<compass_msgs::Azimuth> getAzimuth() { return cras::nullopt; }
184  virtual cras::optional<sensor_msgs::MagneticField> getMagneticField() { return cras::nullopt; }
188  virtual cras::optional<RollPitch> getRollPitch() { return cras::nullopt; }
192  virtual cras::optional<geometry_msgs::Vector3> getAcceleration() { return cras::nullopt; }
196  virtual cras::optional<geometry_msgs::Vector3> getAngularVelocity() { return cras::nullopt; }
200  virtual cras::optional<vision_msgs::Detection2DArray> getFaces() { return cras::nullopt; }
201 
205  virtual cras::optional<sensor_msgs::CameraInfo> getCameraInfo() { return cras::nullopt; }
206 
210  virtual cras::optional<sensor_msgs::Imu> getImu() { return cras::nullopt; }
211 
216  virtual cras::optional<geometry_msgs::Transform> getOpticalFrameTF() { return cras::nullopt; }
217 
221  virtual cras::optional<geometry_msgs::Transform> getZeroRollPitchTF() { return cras::nullopt; }
222 
223  // These reserved functions are future-proofing placeholders that allow adding new types of extractable metadata
224  // without breaking binary compatibility of existing extractors. When adding the getter for the new metadata type,
225  // just replace one of these functions.
226  // There are probably a few other steps to do when turning one of the reserved functions into an actual one:
227  // https://www.haiku-os.org/documents/dev/binary_compatibility_3_easy_steps/
228 
229 private:
230  virtual void __reserved0() {}
231  virtual void __reserved1() {}
232  virtual void __reserved2() {}
233  virtual void __reserved3() {}
234  virtual void __reserved4() {}
235  virtual void __reserved5() {}
236  virtual void __reserved6() {}
237  virtual void __reserved7() {}
238  virtual void __reserved8() {}
239  virtual void __reserved9() {}
240 };
241 
259 {
260  using Ptr = std::shared_ptr<TimedMetadataListener>;
261  using ConstPtr = std::shared_ptr<const TimedMetadataListener>;
262 
263  virtual ~TimedMetadataListener();
264 
269  virtual void processRotation(const TimedMetadata<int>& data) {}
274  virtual void processCropFactor(const TimedMetadata<double>& data) {}
279  virtual void processSensorSizeMM(const TimedMetadata<SensorSize>& data) {}
284  virtual void processFocalLength35MM(const TimedMetadata<double>& data) {}
289  virtual void processFocalLengthMM(const TimedMetadata<double>& data) {}
294  virtual void processFocalLengthPx(const TimedMetadata<double>& data) {}
324  virtual void processRollPitch(const TimedMetadata<RollPitch>& data) {}
340 
346 
351  virtual void processImu(const TimedMetadata<sensor_msgs::Imu>& data) {}
352 
358 
364 
365 private:
366  // These reserved functions are future-proofing placeholders that allow adding new callbacks. See MetadataExtractor.
367  virtual void __reserved0() {}
368  virtual void __reserved1() {}
369  virtual void __reserved2() {}
370  virtual void __reserved3() {}
371  virtual void __reserved4() {}
372  virtual void __reserved5() {}
373  virtual void __reserved6() {}
374  virtual void __reserved7() {}
375  virtual void __reserved8() {}
376  virtual void __reserved9() {}
377 };
378 
387 {
388 public:
389  using Ptr = std::shared_ptr<TimedMetadataExtractor>;
390  using ConstPtr = std::shared_ptr<const TimedMetadataExtractor>;
391 
396 
402  virtual void addTimedMetadataListener(const std::shared_ptr<TimedMetadataListener>& listener);
403 
411  virtual void prepareTimedMetadata(const std::unordered_set<MetadataType>& metadataTypes);
412 
422  virtual std::unordered_set<MetadataType> supportedTimedMetadata(
423  const std::unordered_set<MetadataType>& availableMetadata) const = 0;
424 
441  virtual size_t processTimedMetadata(MetadataType type, const StreamTime& maxTime, bool requireOptional);
442 
448  virtual void seekTimedMetadata(const StreamTime& seekTime);
449 
456  virtual bool hasTimedMetadata() const;
457 
458 protected:
459  std::vector<TimedMetadataListener::Ptr> listeners;
460 };
461 
466 {
467  virtual ~MetadataExtractorPlugin() = default;
468 
475 };
476 
477 }
movie_publisher::GNSSFixAndDetail
std::pair< cras::optional< sensor_msgs::NavSatFix >, cras::optional< gps_common::GPSFix > > GNSSFixAndDetail
Definition: metadata_type.h:61
movie_publisher::TimedMetadataListener::processIntrinsicMatrix
virtual void processIntrinsicMatrix(const TimedMetadata< IntrinsicMatrix > &data)
Process the intrinsic calibration matrix of the camera. \data[in] The intrinsic matrix.
Definition: metadata_extractor.h:299
movie_publisher::TimedMetadataListener
Listener of decoded timed metadata.
Definition: metadata_extractor.h:258
movie_publisher::MetadataExtractor::getName
virtual std::string getName() const =0
Return the name of the extractor.
optional.hpp
movie_publisher::MetadataExtractor::__reserved6
virtual void __reserved6()
Definition: metadata_extractor.h:236
movie_publisher::MetadataExtractor::__reserved2
virtual void __reserved2()
Definition: metadata_extractor.h:232
movie_publisher::TimedMetadataListener::processCameraInfo
virtual void processCameraInfo(const TimedMetadata< sensor_msgs::CameraInfo > &data)
Process camera info. \data[in] Camera info data.
Definition: metadata_extractor.h:345
movie_publisher::MetadataExtractor::getLensMake
virtual cras::optional< std::string > getLensMake()
Definition: metadata_extractor.h:132
movie_publisher::MetadataExtractor::MetadataExtractor
MetadataExtractor(const cras::LogHelperPtr &log)
Constructor.
movie_publisher::MetadataExtractor::__reserved0
virtual void __reserved0()
Definition: metadata_extractor.h:230
movie_publisher::TimedMetadataListener::__reserved3
virtual void __reserved3()
Definition: metadata_extractor.h:370
movie_publisher::MetadataExtractorParams::log
cras::LogHelperPtr log
Logger.
Definition: metadata_extractor.h:51
movie_publisher::MovieOpenConfig
Configuration specifying what movie file to open and how.
Definition: movie_open_config.h:28
movie_publisher::TimedMetadataExtractor::processTimedMetadata
virtual size_t processTimedMetadata(MetadataType type, const StreamTime &maxTime, bool requireOptional)
Process timed metadata up until the time passed as parameter.
movie_publisher::TimedMetadataExtractor::TimedMetadataExtractor
TimedMetadataExtractor(const cras::LogHelperPtr &log)
movie_publisher::MetadataExtractor::~MetadataExtractor
virtual ~MetadataExtractor()
movie_publisher::MetadataExtractor::getAngularVelocity
virtual cras::optional< geometry_msgs::Vector3 > getAngularVelocity()
Definition: metadata_extractor.h:196
movie_publisher::TimedMetadataListener::__reserved7
virtual void __reserved7()
Definition: metadata_extractor.h:374
movie_publisher::MetadataExtractor::getZeroRollPitchTF
virtual cras::optional< geometry_msgs::Transform > getZeroRollPitchTF()
Definition: metadata_extractor.h:221
movie_publisher::TimedMetadataListener::~TimedMetadataListener
virtual ~TimedMetadataListener()
movie_publisher::MetadataExtractor
Extractor of metadata about a movie or image.
Definition: metadata_extractor.h:76
movie_publisher::MetadataExtractor::getFocalLength35MM
virtual cras::optional< double > getFocalLength35MM()
Definition: metadata_extractor.h:156
movie_publisher::MetadataExtractorPlugin::getExtractor
virtual MetadataExtractor::Ptr getExtractor(const MetadataExtractorParams &params)=0
Instantiate the extractor with the given parameters.
movie_publisher::MetadataExtractor::getFocalLengthPx
virtual cras::optional< double > getFocalLengthPx()
Definition: metadata_extractor.h:164
movie_info.h
Basic information about an open movie.
movie_publisher::TimedMetadata
Timestamping wrapper for any kind of metadata.
Definition: metadata_type.h:72
movie_publisher::MetadataExtractor::getRotation
virtual cras::optional< int > getRotation()
Definition: metadata_extractor.h:140
time.h
movie_publisher::MetadataExtractor::getCameraModel
virtual cras::optional< std::string > getCameraModel()
Definition: metadata_extractor.h:128
movie_publisher::MetadataExtractorPlugin::~MetadataExtractorPlugin
virtual ~MetadataExtractorPlugin()=default
movie_publisher::MetadataExtractorParams::cache
std::shared_ptr< MetadataCache > cache
Cache of latest and timed metadata.
Definition: metadata_extractor.h:56
movie_publisher::MetadataExtractor::__reserved4
virtual void __reserved4()
Definition: metadata_extractor.h:234
movie_publisher::TimedMetadataListener::processAzimuth
virtual void processAzimuth(const TimedMetadata< compass_msgs::Azimuth > &data)
Process the azimuth describing global camera heading when capturing the frame. \data[in] The azimuth.
Definition: metadata_extractor.h:314
cras::HasLogger
movie_publisher::MetadataExtractor::getGNSSPosition
virtual GNSSFixAndDetail getGNSSPosition()
Definition: metadata_extractor.h:176
movie_publisher::MetadataExtractor::getCameraGeneralName
virtual cras::optional< std::string > getCameraGeneralName()
Definition: metadata_extractor.h:111
movie_publisher::TimedMetadataListener::processAngularVelocity
virtual void processAngularVelocity(const TimedMetadata< geometry_msgs::Vector3 > &data)
Process the angular velocity acting on the camera when capturing the frame. \data[in] The angular vel...
Definition: metadata_extractor.h:334
movie_publisher::MetadataExtractor::getAzimuth
virtual cras::optional< compass_msgs::Azimuth > getAzimuth()
Definition: metadata_extractor.h:180
movie_publisher::MetadataExtractor::ConstPtr
std::shared_ptr< const MetadataExtractor > ConstPtr
Definition: metadata_extractor.h:80
movie_publisher::TimedMetadataListener::processFocalLengthPx
virtual void processFocalLengthPx(const TimedMetadata< double > &data)
Process the focal length expressed in pixels. \data[in] The focal length [px].
Definition: metadata_extractor.h:294
movie_publisher::TimedMetadataListener::__reserved9
virtual void __reserved9()
Definition: metadata_extractor.h:376
movie_publisher::MetadataExtractor::getLensModel
virtual cras::optional< std::string > getLensModel()
Definition: metadata_extractor.h:136
movie_publisher::MetadataExtractor::getCameraMake
virtual cras::optional< std::string > getCameraMake()
Definition: metadata_extractor.h:124
movie_publisher::MetadataExtractor::processPacket
virtual void processPacket(const AVPacket *packet)
Optional processing of libav packets as they are read from the movie file.
Definition: metadata_extractor.h:106
movie_publisher::TimedMetadataListener::processDistortion
virtual void processDistortion(const TimedMetadata< DistortionData > &data)
Process the camera distortion coefficients (corresponding to the OpenCV calibration model)....
Definition: metadata_extractor.h:304
movie_publisher::TimedMetadataListener::processImu
virtual void processImu(const TimedMetadata< sensor_msgs::Imu > &data)
Process IMU data. \data[in] IMU data.
Definition: metadata_extractor.h:351
movie_publisher::StreamTime
Time type denoting movie stream time.
Definition: types.h:115
log_utils.h
movie_publisher::TimedMetadataExtractor::supportedTimedMetadata
virtual std::unordered_set< MetadataType > supportedTimedMetadata(const std::unordered_set< MetadataType > &availableMetadata) const =0
Get a list of timed metadata that are supported by this instance of the extractor based on the given ...
movie_publisher::TimedMetadataListener::processRotation
virtual void processRotation(const TimedMetadata< int > &data)
Process the rotation of the image. \data[in] Rotation of the image in degrees. Only values 0,...
Definition: metadata_extractor.h:269
movie_publisher::TimedMetadataListener::processFaces
virtual void processFaces(const TimedMetadata< vision_msgs::Detection2DArray > &data)
Process faces detected in the scene. \data[in] The faces that were detected.
Definition: metadata_extractor.h:339
movie_publisher::TimedMetadataExtractor::addTimedMetadataListener
virtual void addTimedMetadataListener(const std::shared_ptr< TimedMetadataListener > &listener)
Add a new timed metadata listener.
movie_publisher::TimedMetadataListener::processRollPitch
virtual void processRollPitch(const TimedMetadata< RollPitch > &data)
Process gravity-aligned roll and pitch of the camera when capturing the frame. \data[in] Roll,...
Definition: metadata_extractor.h:324
movie_publisher::TimedMetadataListener::processCropFactor
virtual void processCropFactor(const TimedMetadata< double > &data)
Process crop factor of the camera (i.e. how many times is the sensing area smaller than 36x24 mm)....
Definition: metadata_extractor.h:274
movie_publisher::TimedMetadataListener::processGNSSPosition
virtual void processGNSSPosition(const TimedMetadata< GNSSFixAndDetail > &data)
Process the GNSS position of the camera when capturing the frame. \data[in] The GNSS position.
Definition: metadata_extractor.h:309
movie_open_config.h
Configuration specifying what movie file to open and how.
movie_publisher::TimedMetadataListener::processFocalLengthMM
virtual void processFocalLengthMM(const TimedMetadata< double > &data)
Process the focal length in mm. \data[in] The focal length [mm].
Definition: metadata_extractor.h:289
movie_publisher::MetadataExtractor::getOpticalFrameTF
virtual cras::optional< geometry_msgs::Transform > getOpticalFrameTF()
Definition: metadata_extractor.h:216
movie_publisher::MetadataExtractor::getCameraInfo
virtual cras::optional< sensor_msgs::CameraInfo > getCameraInfo()
Definition: metadata_extractor.h:205
movie_publisher::TimedMetadataListener::__reserved1
virtual void __reserved1()
Definition: metadata_extractor.h:368
movie_publisher::MetadataExtractor::getDistortion
virtual cras::optional< DistortionData > getDistortion()
Definition: metadata_extractor.h:172
movie_publisher::TimedMetadataListener::processOpticalFrameTF
virtual void processOpticalFrameTF(const TimedMetadata< geometry_msgs::Transform > &data)
Process the optical frame transform (might be affected by image rotation). \data[in] Transform betwee...
Definition: metadata_extractor.h:357
movie_publisher::MetadataExtractor::getPriority
virtual int getPriority() const =0
Return the priority of the extractor (for ordering in MetadataManager).
movie_publisher::MetadataExtractorParams::info
MovieInfo::ConstPtr info
Basic information about the open movie.
Definition: metadata_extractor.h:54
movie_publisher::TimedMetadataListener::Ptr
std::shared_ptr< TimedMetadataListener > Ptr
Definition: metadata_extractor.h:260
movie_publisher::TimedMetadataListener::__reserved6
virtual void __reserved6()
Definition: metadata_extractor.h:373
movie_publisher::MetadataExtractor::getCreationTime
virtual cras::optional< ros::Time > getCreationTime()
Definition: metadata_extractor.h:144
bound_param_helper.hpp
movie_publisher::MetadataExtractor::getImu
virtual cras::optional< sensor_msgs::Imu > getImu()
Definition: metadata_extractor.h:210
movie_publisher::TimedMetadataListener::processAcceleration
virtual void processAcceleration(const TimedMetadata< geometry_msgs::Vector3 > &data)
Process the acceleration vector acting on the camera when capturing the frame (including gravity)....
Definition: metadata_extractor.h:329
movie_publisher::MovieInfo::ConstPtr
std::shared_ptr< const MovieInfo > ConstPtr
Definition: movie_info.h:195
movie_publisher::TimedMetadataListener::__reserved0
virtual void __reserved0()
Definition: metadata_extractor.h:367
movie_publisher::TimedMetadataListener::processZeroRollPitchTF
virtual void processZeroRollPitchTF(const TimedMetadata< geometry_msgs::Transform > &data)
Process the transform from camera body frame to a gravity-aligned frame. \data[in] The transform from...
Definition: metadata_extractor.h:363
movie_publisher::MetadataExtractor::__reserved8
virtual void __reserved8()
Definition: metadata_extractor.h:238
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
movie_publisher::TimedMetadataListener::processFocalLength35MM
virtual void processFocalLength35MM(const TimedMetadata< double > &data)
Process the focal length recomputed to an equivalent 35 mm system. \data[in] The focal length 35 mm e...
Definition: metadata_extractor.h:284
movie_publisher::TimedMetadataListener::processMagneticField
virtual void processMagneticField(const TimedMetadata< sensor_msgs::MagneticField > &data)
Process the magnetic field acting on the camera. \data[in] The magnetic field measurement in X,...
Definition: metadata_extractor.h:319
movie_publisher::MetadataExtractor::Ptr
std::shared_ptr< MetadataExtractor > Ptr
Definition: metadata_extractor.h:79
movie_publisher::MetadataExtractor::getAcceleration
virtual cras::optional< geometry_msgs::Vector3 > getAcceleration()
Definition: metadata_extractor.h:192
movie_publisher::MetadataExtractor::__reserved9
virtual void __reserved9()
Definition: metadata_extractor.h:239
movie_publisher::TimedMetadataExtractor::prepareTimedMetadata
virtual void prepareTimedMetadata(const std::unordered_set< MetadataType > &metadataTypes)
Perform any required initialization of the extractor so that it is prepared to extract metadata of th...
movie_publisher
Definition: ExifBaseMetadataExtractor.h:27
movie_publisher::TimedMetadataExtractor::hasTimedMetadata
virtual bool hasTimedMetadata() const
movie_publisher::TimedMetadataListener::__reserved8
virtual void __reserved8()
Definition: metadata_extractor.h:375
movie_publisher::MetadataExtractor::getRollPitch
virtual cras::optional< RollPitch > getRollPitch()
Definition: metadata_extractor.h:188
movie_publisher::MetadataExtractor::getFaces
virtual cras::optional< vision_msgs::Detection2DArray > getFaces()
Definition: metadata_extractor.h:200
movie_publisher::TimedMetadataListener::__reserved5
virtual void __reserved5()
Definition: metadata_extractor.h:372
movie_publisher::MetadataExtractorParams::manager
std::weak_ptr< MetadataManager > manager
Weak pointer to the metadata manager. Use it to call other extractors.
Definition: metadata_extractor.h:52
movie_publisher::TimedMetadataExtractor
Extractor of timed metadata.
Definition: metadata_extractor.h:386
movie_publisher::MetadataExtractor::getMagneticField
virtual cras::optional< sensor_msgs::MagneticField > getMagneticField()
Definition: metadata_extractor.h:184
movie_publisher::MetadataExtractor::getSensorSizeMM
virtual cras::optional< SensorSize > getSensorSizeMM()
Definition: metadata_extractor.h:152
movie_publisher::MetadataType
MetadataType
Enum for supported metadata.
Definition: metadata_type.h:26
movie_publisher::MetadataExtractorParams::config
MovieOpenConfig config
Configuration with which the movie was opened.
Definition: metadata_extractor.h:53
cras::HasLogger::log
::cras::LogHelperPtr log
metadata_cache.h
Metadata cache.
movie_publisher::TimedMetadataListener::__reserved4
virtual void __reserved4()
Definition: metadata_extractor.h:371
movie_publisher::MetadataExtractor::getCropFactor
virtual cras::optional< double > getCropFactor()
Definition: metadata_extractor.h:148
movie_publisher::MetadataExtractorPlugin
Helper structure that handles instantiation of an extractor.
Definition: metadata_extractor.h:465
movie_publisher::TimedMetadataListener::processSensorSizeMM
virtual void processSensorSizeMM(const TimedMetadata< SensorSize > &data)
Process the sensor physical size. \data[in] Sensor size in mm (width, height).
Definition: metadata_extractor.h:279
movie_publisher::TimedMetadataListener::__reserved2
virtual void __reserved2()
Definition: metadata_extractor.h:369
movie_publisher::MetadataExtractor::getCameraSerialNumber
virtual cras::optional< std::string > getCameraSerialNumber()
Definition: metadata_extractor.h:120
movie_publisher::MetadataExtractor::__reserved1
virtual void __reserved1()
Definition: metadata_extractor.h:231
movie_publisher::MetadataExtractor::__reserved5
virtual void __reserved5()
Definition: metadata_extractor.h:235
movie_publisher::MetadataExtractor::__reserved7
virtual void __reserved7()
Definition: metadata_extractor.h:237
movie_publisher::MetadataExtractor::getFocalLengthMM
virtual cras::optional< double > getFocalLengthMM()
Definition: metadata_extractor.h:160
metadata_type.h
Types of metadata.
movie_publisher::MetadataExtractorParams
Parameters passed to the extractor plugins when initializing them.
Definition: metadata_extractor.h:49
movie_publisher::TimedMetadataListener::ConstPtr
std::shared_ptr< const TimedMetadataListener > ConstPtr
Definition: metadata_extractor.h:261
movie_publisher::TimedMetadataExtractor::seekTimedMetadata
virtual void seekTimedMetadata(const StreamTime &seekTime)
Seek timed metadata to the given stream time.
movie_publisher::MetadataExtractorParams::avFormatContext
const AVFormatContext * avFormatContext
Libav context of the open movie.
Definition: metadata_extractor.h:55
movie_publisher::MetadataExtractor::__reserved3
virtual void __reserved3()
Definition: metadata_extractor.h:233
movie_publisher::MetadataExtractor::getIntrinsicMatrix
virtual cras::optional< IntrinsicMatrix > getIntrinsicMatrix()
Definition: metadata_extractor.h:168
movie_publisher::TimedMetadataExtractor::listeners
std::vector< TimedMetadataListener::Ptr > listeners
The listeners whose callbacks should be called.
Definition: metadata_extractor.h:459
movie_publisher::MetadataExtractor::getCameraUniqueName
virtual cras::optional< std::string > getCameraUniqueName()
Definition: metadata_extractor.h:116


movie_publisher
Author(s): Martin Pecka
autogenerated on Wed May 28 2025 02:07:22