metadata_manager.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 "metadata_extractor.h"
13 
14 #include <deque>
15 #include <memory>
16 #include <set>
17 #include <string>
18 #include <utility>
19 
20 #include <compass_msgs/Azimuth.h>
23 #include <geometry_msgs/Transform.h>
26 #include <ros/time.h>
27 #include <sensor_msgs/CameraInfo.h>
28 #include <sensor_msgs/Imu.h>
29 #include <sensor_msgs/MagneticField.h>
30 #include <vision_msgs/Detection2DArray.h>
31 
32 namespace movie_publisher
33 {
34 
35 class StackGuard;
36 struct CachingMetadataListener;
37 
39 {
41  {
42  if (lhs == nullptr)
43  return true;
44  if (rhs == nullptr)
45  return false;
46  return lhs->getPriority() < rhs->getPriority();
47  }
48 };
49 
66 {
67 public:
75  ~MetadataManager() override;
76 
81  void addExtractor(const std::shared_ptr<MetadataExtractor>& extractor);
82 
88 
93  std::shared_ptr<MetadataCache> getCache();
94 
99 
100  void prepareTimedMetadata(const std::unordered_set<MetadataType>& metadataTypes) override;
101  std::unordered_set<MetadataType> supportedTimedMetadata(
102  const std::unordered_set<MetadataType>& availableMetadata) const override;
103  size_t processTimedMetadata(MetadataType type, const StreamTime& maxTime, bool requireOptional) override;
104  void seekTimedMetadata(const StreamTime& seekTime) override;
105  bool hasTimedMetadata() const override;
106  void processPacket(const AVPacket* packet) override;
107 
108  std::string getName() const override;
109  int getPriority() const override;
110 
111  cras::optional<std::string> getCameraGeneralName() override;
112  cras::optional<std::string> getCameraUniqueName() override;
113  cras::optional<std::string> getCameraSerialNumber() override;
114  cras::optional<std::string> getCameraMake() override;
115  cras::optional<std::string> getCameraModel() override;
116  cras::optional<std::string> getLensMake() override;
117  cras::optional<std::string> getLensModel() override;
118  cras::optional<int> getRotation() override;
119  cras::optional<ros::Time> getCreationTime() override;
120  cras::optional<double> getCropFactor() override;
121  cras::optional<SensorSize> getSensorSizeMM() override;
122  cras::optional<double> getFocalLength35MM() override;
123  cras::optional<double> getFocalLengthPx() override;
124  cras::optional<double> getFocalLengthMM() override;
125  cras::optional<IntrinsicMatrix> getIntrinsicMatrix() override;
126  cras::optional<std::pair<DistortionType, Distortion>> getDistortion() override;
128  cras::optional<sensor_msgs::MagneticField> getMagneticField() override;
129  cras::optional<compass_msgs::Azimuth> getAzimuth() override;
130  cras::optional<RollPitch> getRollPitch() override;
131  cras::optional<geometry_msgs::Vector3> getAngularVelocity() override;
132  cras::optional<geometry_msgs::Vector3> getAcceleration() override;
133  cras::optional<vision_msgs::Detection2DArray> getFaces() override;
134  cras::optional<sensor_msgs::CameraInfo> getCameraInfo() override;
135  cras::optional<sensor_msgs::Imu> getImu() override;
136  cras::optional<geometry_msgs::Transform> getOpticalFrameTF() override;
137  cras::optional<geometry_msgs::Transform> getZeroRollPitchTF() override;
138 
139 protected:
146  bool stopRecursion(const std::string& fn, const MetadataExtractor* extractor) const;
147 
157  template<typename T, typename O = cras::optional<T>>
158  T checkExtractors(const std::string& func,
159  T(MetadataExtractor::*getFn)(), O(LatestMetadataCache::*getFnLatest)(), const std::string& frame = "");
160 
162  std::multiset<MetadataExtractor::Ptr, PriorityComparator> extractors;
163  std::multiset<TimedMetadataExtractor::Ptr, PriorityComparator> timedExtractors;
165  std::deque<std::pair<std::string, const MetadataExtractor*>> callStack;
166  size_t width {0u};
167  size_t height {0u};
168 
171  std::shared_ptr<MetadataCache> cache;
172 
174  std::shared_ptr<CachingMetadataListener> metadataListener;
175 
176  friend StackGuard;
177 };
178 
183 {
184 public:
191  StackGuard(decltype(MetadataManager::callStack)& stack, const std::string& fn, const MetadataExtractor* extractor);
192  ~StackGuard();
193 private:
194  std::string getStackDescription() const;
196  std::string fn;
198 };
199 }
movie_publisher::GNSSFixAndDetail
std::pair< cras::optional< sensor_msgs::NavSatFix >, cras::optional< gps_common::GPSFix > > GNSSFixAndDetail
Definition: metadata_type.h:61
movie_publisher::MetadataManager::StackGuard
friend StackGuard
Definition: metadata_manager.h:176
optional.hpp
movie_publisher::MovieOpenConfig
Configuration specifying what movie file to open and how.
Definition: movie_open_config.h:28
movie_publisher::MetadataManager::getCache
std::shared_ptr< MetadataCache > getCache()
Return the metadata cache.
movie_publisher::StackGuard::fn
std::string fn
The called function.
Definition: metadata_manager.h:196
movie_publisher::MetadataManager::getName
std::string getName() const override
Return the name of the extractor.
movie_publisher::MetadataManager::getMagneticField
cras::optional< sensor_msgs::MagneticField > getMagneticField() override
movie_publisher::MetadataExtractor
Extractor of metadata about a movie or image.
Definition: metadata_extractor.h:76
movie_publisher::MetadataManager::getLensMake
cras::optional< std::string > getLensMake() override
time.h
movie_publisher::MetadataManager::metadataListener
std::shared_ptr< CachingMetadataListener > metadataListener
The timed metadata listener proxy passed to all timed extractors to collect and cache their output.
Definition: metadata_manager.h:174
movie_publisher::MetadataManager::processPacket
void processPacket(const AVPacket *packet) override
Optional processing of libav packets as they are read from the movie file.
movie_publisher::MetadataManager::clearTimedMetadataCache
void clearTimedMetadataCache()
Clear all cached timed metadata.
movie_publisher::MetadataManager::MetadataManager
MetadataManager(const cras::LogHelperPtr &log, const MovieOpenConfig &config, const MovieInfo::ConstPtr &info)
Constructor. Each movie should have its own manager.
movie_publisher::MetadataManager::cache
std::shared_ptr< MetadataCache > cache
Cache of static and timed metadata.
Definition: metadata_manager.h:171
movie_publisher::MetadataManager::getCameraInfo
cras::optional< sensor_msgs::CameraInfo > getCameraInfo() override
movie_publisher::StackGuard::getStackDescription
std::string getStackDescription() const
Get a human-readable representation of the whole call stack.
movie_publisher::MetadataManager::timedExtractors
std::multiset< TimedMetadataExtractor::Ptr, PriorityComparator > timedExtractors
Registered timed extractor instances.
Definition: metadata_manager.h:164
movie_publisher::MetadataManager::getAzimuth
cras::optional< compass_msgs::Azimuth > getAzimuth() override
movie_publisher::MetadataManager::getAcceleration
cras::optional< geometry_msgs::Vector3 > getAcceleration() override
movie_publisher::MetadataManager::info
MovieInfo::ConstPtr info
Information about the open movie.
Definition: metadata_manager.h:170
movie_publisher::MetadataManager::getCameraMake
cras::optional< std::string > getCameraMake() override
movie_publisher::MetadataExtractor::ConstPtr
std::shared_ptr< const MetadataExtractor > ConstPtr
Definition: metadata_extractor.h:80
movie_publisher::MetadataManager::getIntrinsicMatrix
cras::optional< IntrinsicMatrix > getIntrinsicMatrix() override
movie_publisher::MetadataManager::supportedTimedMetadata
std::unordered_set< MetadataType > supportedTimedMetadata(const std::unordered_set< MetadataType > &availableMetadata) const override
Get a list of timed metadata that are supported by this instance of the extractor based on the given ...
movie_publisher::MetadataManager::height
size_t height
Height of the analyzed movie [px].
Definition: metadata_manager.h:167
movie_publisher::StreamTime
Time type denoting movie stream time.
Definition: types.h:115
log_utils.h
movie_publisher::MetadataManager::addExtractor
void addExtractor(const std::shared_ptr< MetadataExtractor > &extractor)
Register a new extractor.
movie_publisher::MetadataManager::processTimedMetadata
size_t processTimedMetadata(MetadataType type, const StreamTime &maxTime, bool requireOptional) override
Process timed metadata up until the time passed as parameter.
movie_publisher::MetadataManager::getCameraSerialNumber
cras::optional< std::string > getCameraSerialNumber() override
movie_publisher::MetadataManager::getFocalLengthPx
cras::optional< double > getFocalLengthPx() override
movie_publisher::StackGuard::~StackGuard
~StackGuard()
metadata_extractor.h
Extractor of image or movie metadata.
movie_publisher::MetadataManager::getCreationTime
cras::optional< ros::Time > getCreationTime() override
movie_publisher::StackGuard
RAII guard saving a function call to stack. Can be used to protect against infinite recursion.
Definition: metadata_manager.h:182
movie_publisher::MetadataManager::getPriority
int getPriority() const override
Return the priority of the extractor (for ordering in MetadataManager).
movie_publisher::MetadataManager
Manager of multiple image metadata providers which can cooperate in parsing.
Definition: metadata_manager.h:65
movie_publisher::MetadataManager::getRotation
cras::optional< int > getRotation() override
movie_publisher::StackGuard::stack
decltype(MetadataManager::callStack) & stack
The stack to operate on.
Definition: metadata_manager.h:195
movie_publisher::MetadataManager::loadExtractorPlugins
void loadExtractorPlugins(const MetadataExtractorParams &params)
Load all known extractors from plugins.
movie_publisher::MetadataManager::callStack
std::deque< std::pair< std::string, const MetadataExtractor * > > callStack
The stack of all calls via the manager.
Definition: metadata_manager.h:165
movie_publisher::MetadataManager::getFaces
cras::optional< vision_msgs::Detection2DArray > getFaces() override
pluginlib::ClassLoader
movie_publisher::LatestMetadataCache
Latest metadata of each type.
Definition: metadata_cache.h:32
class_loader.hpp
movie_publisher::MetadataManager::hasTimedMetadata
bool hasTimedMetadata() const override
movie_publisher::MetadataManager::getDistortion
cras::optional< std::pair< DistortionType, Distortion > > getDistortion() override
movie_publisher::MetadataManager::prepareTimedMetadata
void prepareTimedMetadata(const std::unordered_set< MetadataType > &metadataTypes) override
Perform any required initialization of the extractor so that it is prepared to extract metadata of th...
movie_publisher::MovieInfo::ConstPtr
std::shared_ptr< const MovieInfo > ConstPtr
Definition: movie_info.h:195
movie_publisher::MetadataManager::getAngularVelocity
cras::optional< geometry_msgs::Vector3 > getAngularVelocity() override
movie_publisher::MetadataManager::loader
pluginlib::ClassLoader< MetadataExtractorPlugin > loader
The extractor plugin loader.
Definition: metadata_manager.h:161
movie_publisher::MetadataManager::width
size_t width
Width of the analyzed movie [px].
Definition: metadata_manager.h:166
movie_publisher::MetadataManager::seekTimedMetadata
void seekTimedMetadata(const StreamTime &seekTime) override
Seek timed metadata to the given stream time.
movie_publisher::MetadataManager::getGNSSPosition
GNSSFixAndDetail getGNSSPosition() override
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
movie_publisher::PriorityComparator
Definition: metadata_manager.h:38
movie_publisher
Definition: ExifBaseMetadataExtractor.h:27
movie_publisher::MetadataManager::~MetadataManager
~MetadataManager() override
movie_publisher::MetadataManager::getCameraModel
cras::optional< std::string > getCameraModel() override
movie_publisher::StackGuard::extractor
const MetadataExtractor * extractor
The extractor that calls the function.
Definition: metadata_manager.h:197
movie_publisher::StackGuard::StackGuard
StackGuard(decltype(MetadataManager::callStack)&stack, const std::string &fn, const MetadataExtractor *extractor)
Constructor.
movie_publisher::MetadataManager::getSensorSizeMM
cras::optional< SensorSize > getSensorSizeMM() override
movie_publisher::MetadataManager::getCameraUniqueName
cras::optional< std::string > getCameraUniqueName() override
movie_publisher::MetadataManager::getFocalLength35MM
cras::optional< double > getFocalLength35MM() override
movie_publisher::MetadataManager::getZeroRollPitchTF
cras::optional< geometry_msgs::Transform > getZeroRollPitchTF() override
movie_publisher::TimedMetadataExtractor
Extractor of timed metadata.
Definition: metadata_extractor.h:386
movie_publisher::MetadataManager::getCropFactor
cras::optional< double > getCropFactor() override
movie_publisher::PriorityComparator::operator()
bool operator()(const MetadataExtractor::ConstPtr &lhs, const MetadataExtractor::ConstPtr &rhs) const
Definition: metadata_manager.h:40
movie_publisher::MetadataType
MetadataType
Enum for supported metadata.
Definition: metadata_type.h:26
cras::HasLogger::log
::cras::LogHelperPtr log
metadata_cache.h
Metadata cache.
movie_publisher::MetadataManager::checkExtractors
T checkExtractors(const std::string &func, T(MetadataExtractor::*getFn)(), O(LatestMetadataCache::*getFnLatest)(), const std::string &frame="")
Call the given function in all extractors and return and cache the first valid result.
movie_publisher::MetadataManager::getRollPitch
cras::optional< RollPitch > getRollPitch() override
movie_publisher::MetadataManager::getCameraGeneralName
cras::optional< std::string > getCameraGeneralName() override
movie_publisher::MetadataManager::config
MovieOpenConfig config
Configuration of the open movie.
Definition: metadata_manager.h:169
movie_publisher::MetadataManager::getFocalLengthMM
cras::optional< double > getFocalLengthMM() override
movie_publisher::MetadataManager::getOpticalFrameTF
cras::optional< geometry_msgs::Transform > getOpticalFrameTF() override
movie_publisher::MetadataManager::extractors
std::multiset< MetadataExtractor::Ptr, PriorityComparator > extractors
Definition: metadata_manager.h:162
movie_publisher::MetadataManager::stopRecursion
bool stopRecursion(const std::string &fn, const MetadataExtractor *extractor) const
Check for infinite recursion when individual extractors call common methods via this manager.
movie_publisher::MetadataManager::getImu
cras::optional< sensor_msgs::Imu > getImu() override
movie_publisher::MetadataManager::getLensModel
cras::optional< std::string > getLensModel() override
movie_publisher::MetadataExtractorParams
Parameters passed to the extractor plugins when initializing them.
Definition: metadata_extractor.h:49


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