ExifBaseMetadataExtractor.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 <memory>
13 #include <string>
14 
15 #include <compass_msgs/Azimuth.h>
19 #include <ros/time.h>
20 #include <sensor_msgs/NavSatFix.h>
21 
22 namespace compass_conversions
23 {
24 class CompassConverter;
25 }
26 
27 namespace movie_publisher
28 {
29 
30 typedef std::string ExifAscii;
31 typedef uint8_t ExifByte;
32 typedef uint16_t ExifShort;
33 typedef int16_t ExifSShort;
34 typedef uint32_t ExifLong;
35 typedef int32_t ExifSLong;
36 typedef double ExifRational;
37 typedef double ExifSRational;
38 typedef std::vector<uint8_t> ExifUnknown;
39 
40 template<typename T>
41 struct ExifData
42 {
43  std::string key;
44  T value;
45 };
46 
47 struct ExifBaseMetadataExtractorPrivate;
48 
56 {
57 public:
66  const cras::LogHelperPtr& log, const std::weak_ptr<MetadataManager>& manager, size_t width, size_t height);
67  ~ExifBaseMetadataExtractor() override;
68 
69  cras::optional<ros::Time> getCreationTime() override;
70  cras::optional<std::string> getCameraSerialNumber() override;
71  cras::optional<std::string> getCameraMake() override;
72  cras::optional<std::string> getCameraModel() override;
73  cras::optional<std::string> getLensMake() override;
74  cras::optional<std::string> getLensModel() override;
75  cras::optional<int> getRotation() override;
76  cras::optional<double> getCropFactor() override;
77  cras::optional<std::pair<double, double>> getSensorSizeMM() override;
78  cras::optional<double> getFocalLength35MM() override;
79  cras::optional<double> getFocalLengthMM() override;
80  std::pair<cras::optional<sensor_msgs::NavSatFix>, cras::optional<gps_common::GPSFix>> getGNSSPosition() override;
81  cras::optional<compass_msgs::Azimuth> getAzimuth() override;
82  cras::optional<std::pair<double, double>> getRollPitch() override;
83  cras::optional<geometry_msgs::Vector3> getAcceleration() override;
84 
85 protected:
86  size_t width;
87  size_t height;
88 
97 
102  virtual cras::optional<double> getGPSLatitude();
107  virtual cras::optional<double> getGPSLongitude();
112  virtual cras::optional<double> getGPSAltitude();
117  virtual cras::optional<double> getGPSSpeed();
122  virtual cras::optional<double> getGPSTrack();
128  virtual cras::optional<double> getGPSImgDirection();
133  virtual cras::optional<std::string> getGPSImgDirectionRef();
138  virtual cras::optional<ros::Time> getGPSTime();
139 
140  // Methods to be implemented by subclasses.
141 
145  virtual cras::optional<ExifData<ExifAscii>> getExifMake() {return cras::nullopt;}
149  virtual cras::optional<ExifData<ExifAscii>> getExifModel() {return cras::nullopt;}
153  virtual cras::optional<ExifData<ExifAscii>> getExifLensMake() {return cras::nullopt;}
157  virtual cras::optional<ExifData<ExifAscii>> getExifLensModel() {return cras::nullopt;}
161  virtual cras::optional<ExifData<ExifAscii>> getExifBodySerialNumber() {return cras::nullopt;}
165  virtual cras::optional<ExifData<ExifAscii>> getExifLensSerialNumber() {return cras::nullopt;}
169  virtual cras::optional<ExifData<ExifAscii>> getExifDateTimeOriginal() {return cras::nullopt;}
173  virtual cras::optional<ExifData<ExifAscii>> getExifOffsetTimeOriginal() {return cras::nullopt;}
177  virtual cras::optional<ExifData<ExifAscii>> getExifSubSecTimeOriginal() {return cras::nullopt;}
181  virtual cras::optional<ExifData<ExifShort>> getExifOrientation() {return cras::nullopt;}
185  virtual cras::optional<ExifData<ExifRational>> getExifFocalPlaneXRes() {return cras::nullopt;}
189  virtual cras::optional<ExifData<ExifRational>> getExifFocalPlaneYRes() {return cras::nullopt;}
193  virtual cras::optional<ExifData<ExifShort>> getExifFocalPlaneResUnit() {return cras::nullopt;}
197  virtual cras::optional<ExifData<ExifShort>> getExifResUnit() {return cras::nullopt;}
201  virtual cras::optional<ExifData<ExifShort>> getExifFocalLength35MM() {return cras::nullopt;}
205  virtual cras::optional<ExifData<ExifRational>> getExifFocalLength() {return cras::nullopt;}
209  virtual cras::optional<ExifData<ExifAscii>> getExifGpsLatRef() {return cras::nullopt;}
213  virtual cras::optional<ExifData<ExifRational>> getExifGpsLat(size_t n) {return cras::nullopt;}
217  virtual cras::optional<ExifData<ExifAscii>> getExifGpsLonRef() {return cras::nullopt;}
221  virtual cras::optional<ExifData<ExifRational>> getExifGpsLon(size_t n) {return cras::nullopt;}
225  virtual cras::optional<ExifData<ExifByte>> getExifGpsAltRef() {return cras::nullopt;}
229  virtual cras::optional<ExifData<ExifRational>> getExifGpsAlt() {return cras::nullopt;}
233  virtual cras::optional<ExifData<ExifAscii>> getExifGpsMeasureMode() {return cras::nullopt;}
237  virtual cras::optional<ExifData<ExifRational>> getExifGpsDOP() {return cras::nullopt;}
241  virtual cras::optional<ExifData<ExifAscii>> getExifGpsSpeedRef() {return cras::nullopt;}
245  virtual cras::optional<ExifData<ExifRational>> getExifGpsSpeed() {return cras::nullopt;}
249  virtual cras::optional<ExifData<ExifAscii>> getExifGpsTrackRef() {return cras::nullopt;}
253  virtual cras::optional<ExifData<ExifRational>> getExifGpsTrack() {return cras::nullopt;}
257  virtual cras::optional<ExifData<ExifRational>> getExifGpsTimeStamp(size_t n) {return cras::nullopt;}
261  virtual cras::optional<ExifData<ExifAscii>> getExifGpsDateStamp() {return cras::nullopt;}
265  virtual cras::optional<ExifData<ExifShort>> getExifGpsDifferential() {return cras::nullopt;}
269  virtual cras::optional<ExifData<ExifRational>> getExifGpsHPositioningError() {return cras::nullopt;}
273  virtual cras::optional<ExifData<ExifAscii>> getExifGpsImgDirectionRef() {return cras::nullopt;}
277  virtual cras::optional<ExifData<ExifRational>> getExifGpsImgDirection() {return cras::nullopt;}
281  virtual cras::optional<ExifData<ExifSRational>> getExifAcceleration(size_t n) {return cras::nullopt;}
285  virtual cras::optional<ExifData<ExifSRational>> getExifRollAngle() {return cras::nullopt;}
289  virtual cras::optional<ExifData<ExifSRational>> getExifPitchAngle() {return cras::nullopt;}
290 
291 private:
292  std::unique_ptr<ExifBaseMetadataExtractorPrivate> data;
293 };
294 
295 }
optional.hpp
movie_publisher::ExifBaseMetadataExtractor::width
size_t width
Width of the movie [px].
Definition: ExifBaseMetadataExtractor.h:86
movie_publisher::ExifBaseMetadataExtractor::getExifLensMake
virtual cras::optional< ExifData< ExifAscii > > getExifLensMake()
Definition: ExifBaseMetadataExtractor.h:153
movie_publisher::ExifBaseMetadataExtractor::getExifSubSecTimeOriginal
virtual cras::optional< ExifData< ExifAscii > > getExifSubSecTimeOriginal()
Definition: ExifBaseMetadataExtractor.h:177
movie_publisher::ExifBaseMetadataExtractor::getExifLensSerialNumber
virtual cras::optional< ExifData< ExifAscii > > getExifLensSerialNumber()
Definition: ExifBaseMetadataExtractor.h:165
movie_publisher::ExifSLong
int32_t ExifSLong
Definition: ExifBaseMetadataExtractor.h:35
movie_publisher::ExifBaseMetadataExtractor::getExifFocalPlaneXRes
virtual cras::optional< ExifData< ExifRational > > getExifFocalPlaneXRes()
Definition: ExifBaseMetadataExtractor.h:185
movie_publisher::ExifBaseMetadataExtractor::getGPSImgDirectionRef
virtual cras::optional< std::string > getGPSImgDirectionRef()
Get the image direction reference.
movie_publisher::ExifBaseMetadataExtractor::getGPSImgDirection
virtual cras::optional< double > getGPSImgDirection()
GPS image direction from GPSImgDirection.
movie_publisher::ExifSRational
double ExifSRational
Definition: ExifBaseMetadataExtractor.h:37
movie_publisher::ExifBaseMetadataExtractor::getExifLensModel
virtual cras::optional< ExifData< ExifAscii > > getExifLensModel()
Definition: ExifBaseMetadataExtractor.h:157
compass_conversions
movie_publisher::ExifBaseMetadataExtractor::ExifBaseMetadataExtractor
ExifBaseMetadataExtractor(const cras::LogHelperPtr &log, const std::weak_ptr< MetadataManager > &manager, size_t width, size_t height)
Constructor.
movie_publisher::ExifBaseMetadataExtractor::getGPSLatitude
virtual cras::optional< double > getGPSLatitude()
Construct latitude from GPSLatitude and GPSLatitudeRef.
movie_publisher::MetadataExtractor
Extractor of metadata about a movie or image.
Definition: metadata_extractor.h:76
movie_publisher::ExifBaseMetadataExtractor::getCameraModel
cras::optional< std::string > getCameraModel() override
metadata_manager.h
Manager of multiple image metadata providers which can cooperate in parsing.
time.h
movie_publisher::ExifBaseMetadataExtractor::getGPSSpeed
virtual cras::optional< double > getGPSSpeed()
Construct ground speed from GPSSpeed and GPSSpeedRef.
compass_conversions::CompassConverter
movie_publisher::ExifBaseMetadataExtractor::getExifGpsTrack
virtual cras::optional< ExifData< ExifRational > > getExifGpsTrack()
Definition: ExifBaseMetadataExtractor.h:253
movie_publisher::ExifBaseMetadataExtractor::getGPSLongitude
virtual cras::optional< double > getGPSLongitude()
Construct latitude from GPSLongitude and GPSLongitudeRef.
movie_publisher::ExifBaseMetadataExtractor::getExifGpsSpeed
virtual cras::optional< ExifData< ExifRational > > getExifGpsSpeed()
Definition: ExifBaseMetadataExtractor.h:245
movie_publisher::ExifUnknown
std::vector< uint8_t > ExifUnknown
Definition: ExifBaseMetadataExtractor.h:38
movie_publisher::ExifSShort
int16_t ExifSShort
Definition: ExifBaseMetadataExtractor.h:33
movie_publisher::ExifBaseMetadataExtractor::getExifGpsDOP
virtual cras::optional< ExifData< ExifRational > > getExifGpsDOP()
Definition: ExifBaseMetadataExtractor.h:237
movie_publisher::ExifBaseMetadataExtractor::getExifDateTimeOriginal
virtual cras::optional< ExifData< ExifAscii > > getExifDateTimeOriginal()
Definition: ExifBaseMetadataExtractor.h:169
movie_publisher::ExifBaseMetadataExtractor::getExifBodySerialNumber
virtual cras::optional< ExifData< ExifAscii > > getExifBodySerialNumber()
Definition: ExifBaseMetadataExtractor.h:161
movie_publisher::ExifData
Definition: ExifBaseMetadataExtractor.h:41
movie_publisher::ExifBaseMetadataExtractor::getExifGpsMeasureMode
virtual cras::optional< ExifData< ExifAscii > > getExifGpsMeasureMode()
Definition: ExifBaseMetadataExtractor.h:233
movie_publisher::ExifBaseMetadataExtractor::getExifFocalLength35MM
virtual cras::optional< ExifData< ExifShort > > getExifFocalLength35MM()
Definition: ExifBaseMetadataExtractor.h:201
movie_publisher::ExifBaseMetadataExtractor::getCameraSerialNumber
cras::optional< std::string > getCameraSerialNumber() override
movie_publisher::ExifBaseMetadataExtractor::getExifGpsSpeedRef
virtual cras::optional< ExifData< ExifAscii > > getExifGpsSpeedRef()
Definition: ExifBaseMetadataExtractor.h:241
movie_publisher::ExifBaseMetadataExtractor::getExifGpsDifferential
virtual cras::optional< ExifData< ExifShort > > getExifGpsDifferential()
Definition: ExifBaseMetadataExtractor.h:265
movie_publisher::ExifBaseMetadataExtractor::getExifGpsTrackRef
virtual cras::optional< ExifData< ExifAscii > > getExifGpsTrackRef()
Definition: ExifBaseMetadataExtractor.h:249
movie_publisher::ExifBaseMetadataExtractor::getExifGpsTimeStamp
virtual cras::optional< ExifData< ExifRational > > getExifGpsTimeStamp(size_t n)
Definition: ExifBaseMetadataExtractor.h:257
movie_publisher::ExifBaseMetadataExtractor::getAcceleration
cras::optional< geometry_msgs::Vector3 > getAcceleration() override
movie_publisher::ExifBaseMetadataExtractor::data
std::unique_ptr< ExifBaseMetadataExtractorPrivate > data
PIMPL.
Definition: ExifBaseMetadataExtractor.h:292
movie_publisher::ExifBaseMetadataExtractor::getExifGpsLon
virtual cras::optional< ExifData< ExifRational > > getExifGpsLon(size_t n)
Definition: ExifBaseMetadataExtractor.h:221
movie_publisher::ExifBaseMetadataExtractor::getExifOffsetTimeOriginal
virtual cras::optional< ExifData< ExifAscii > > getExifOffsetTimeOriginal()
Definition: ExifBaseMetadataExtractor.h:173
movie_publisher::ExifBaseMetadataExtractor::getExifGpsLat
virtual cras::optional< ExifData< ExifRational > > getExifGpsLat(size_t n)
Definition: ExifBaseMetadataExtractor.h:213
movie_publisher::ExifBaseMetadataExtractor::getCompassConverter
compass_conversions::CompassConverter & getCompassConverter()
Get a helper for converting various azimuth representations and references.
movie_publisher::ExifBaseMetadataExtractor::getCameraMake
cras::optional< std::string > getCameraMake() override
metadata_extractor.h
Extractor of image or movie metadata.
movie_publisher::ExifBaseMetadataExtractor::getRotation
cras::optional< int > getRotation() override
movie_publisher::ExifBaseMetadataExtractor::getGPSAltitude
virtual cras::optional< double > getGPSAltitude()
Construct altitude from GPSAltitude and GPSAltitudeRef.
movie_publisher::ExifBaseMetadataExtractor::getLensModel
cras::optional< std::string > getLensModel() override
movie_publisher::ExifBaseMetadataExtractor::getExifFocalPlaneYRes
virtual cras::optional< ExifData< ExifRational > > getExifFocalPlaneYRes()
Definition: ExifBaseMetadataExtractor.h:189
movie_publisher::ExifBaseMetadataExtractor::getExifOrientation
virtual cras::optional< ExifData< ExifShort > > getExifOrientation()
Definition: ExifBaseMetadataExtractor.h:181
movie_publisher::ExifBaseMetadataExtractor::getExifGpsLatRef
virtual cras::optional< ExifData< ExifAscii > > getExifGpsLatRef()
Definition: ExifBaseMetadataExtractor.h:209
movie_publisher::ExifBaseMetadataExtractor::getExifModel
virtual cras::optional< ExifData< ExifAscii > > getExifModel()
Definition: ExifBaseMetadataExtractor.h:149
movie_publisher::ExifBaseMetadataExtractor::getGPSTime
virtual cras::optional< ros::Time > getGPSTime()
Get the GPS time corresponding to the current frame.
movie_publisher::ExifLong
uint32_t ExifLong
Definition: ExifBaseMetadataExtractor.h:34
movie_publisher::ExifBaseMetadataExtractor::getExifAcceleration
virtual cras::optional< ExifData< ExifSRational > > getExifAcceleration(size_t n)
Definition: ExifBaseMetadataExtractor.h:281
movie_publisher::ExifBaseMetadataExtractor::getSensorSizeMM
cras::optional< std::pair< double, double > > getSensorSizeMM() override
movie_publisher::ExifBaseMetadataExtractor::getExifMake
virtual cras::optional< ExifData< ExifAscii > > getExifMake()
Definition: ExifBaseMetadataExtractor.h:145
movie_publisher::ExifBaseMetadataExtractor::getExifGpsDateStamp
virtual cras::optional< ExifData< ExifAscii > > getExifGpsDateStamp()
Definition: ExifBaseMetadataExtractor.h:261
movie_publisher::ExifBaseMetadataExtractor
Common base for all metadata extractors that utilize EXIF data.
Definition: ExifBaseMetadataExtractor.h:55
movie_publisher::ExifBaseMetadataExtractor::getLensMake
cras::optional< std::string > getLensMake() override
movie_publisher::ExifBaseMetadataExtractor::getExifGpsAltRef
virtual cras::optional< ExifData< ExifByte > > getExifGpsAltRef()
Definition: ExifBaseMetadataExtractor.h:225
movie_publisher::ExifShort
uint16_t ExifShort
Definition: ExifBaseMetadataExtractor.h:32
movie_publisher::ExifBaseMetadataExtractor::getExifRollAngle
virtual cras::optional< ExifData< ExifSRational > > getExifRollAngle()
Definition: ExifBaseMetadataExtractor.h:285
movie_publisher::ExifBaseMetadataExtractor::getExifFocalPlaneResUnit
virtual cras::optional< ExifData< ExifShort > > getExifFocalPlaneResUnit()
Definition: ExifBaseMetadataExtractor.h:193
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
movie_publisher::ExifBaseMetadataExtractor::getExifGpsImgDirectionRef
virtual cras::optional< ExifData< ExifAscii > > getExifGpsImgDirectionRef()
Definition: ExifBaseMetadataExtractor.h:273
movie_publisher::ExifByte
uint8_t ExifByte
Definition: ExifBaseMetadataExtractor.h:31
movie_publisher
Definition: ExifBaseMetadataExtractor.h:27
movie_publisher::ExifBaseMetadataExtractor::getFocalLength35MM
cras::optional< double > getFocalLength35MM() override
movie_publisher::ExifBaseMetadataExtractor::getGPSTrack
virtual cras::optional< double > getGPSTrack()
Construct GPS track (heading) from GPSTrack and GPSTrackRef.
movie_publisher::ExifBaseMetadataExtractor::getExifResUnit
virtual cras::optional< ExifData< ExifShort > > getExifResUnit()
Definition: ExifBaseMetadataExtractor.h:197
movie_publisher::ExifBaseMetadataExtractor::~ExifBaseMetadataExtractor
~ExifBaseMetadataExtractor() override
movie_publisher::ExifBaseMetadataExtractor::getExifGpsLonRef
virtual cras::optional< ExifData< ExifAscii > > getExifGpsLonRef()
Definition: ExifBaseMetadataExtractor.h:217
movie_publisher::ExifBaseMetadataExtractor::getCreationTime
cras::optional< ros::Time > getCreationTime() override
movie_publisher::ExifBaseMetadataExtractor::height
size_t height
Height of the movie [px].
Definition: ExifBaseMetadataExtractor.h:87
cras::HasLogger::log
::cras::LogHelperPtr log
movie_publisher::ExifBaseMetadataExtractor::getExifGpsImgDirection
virtual cras::optional< ExifData< ExifRational > > getExifGpsImgDirection()
Definition: ExifBaseMetadataExtractor.h:277
movie_publisher::ExifData::value
T value
Definition: ExifBaseMetadataExtractor.h:44
movie_publisher::ExifBaseMetadataExtractor::getExifPitchAngle
virtual cras::optional< ExifData< ExifSRational > > getExifPitchAngle()
Definition: ExifBaseMetadataExtractor.h:289
movie_publisher::ExifBaseMetadataExtractor::getGNSSPosition
std::pair< cras::optional< sensor_msgs::NavSatFix >, cras::optional< gps_common::GPSFix > > getGNSSPosition() override
movie_publisher::ExifData::key
std::string key
Definition: ExifBaseMetadataExtractor.h:43
movie_publisher::ExifRational
double ExifRational
Definition: ExifBaseMetadataExtractor.h:36
movie_publisher::ExifBaseMetadataExtractor::getExifFocalLength
virtual cras::optional< ExifData< ExifRational > > getExifFocalLength()
Definition: ExifBaseMetadataExtractor.h:205
movie_publisher::ExifBaseMetadataExtractor::getExifGpsHPositioningError
virtual cras::optional< ExifData< ExifRational > > getExifGpsHPositioningError()
Definition: ExifBaseMetadataExtractor.h:269
movie_publisher::ExifAscii
std::string ExifAscii
Definition: ExifBaseMetadataExtractor.h:30
movie_publisher::ExifBaseMetadataExtractor::getAzimuth
cras::optional< compass_msgs::Azimuth > getAzimuth() override
movie_publisher::ExifBaseMetadataExtractor::getFocalLengthMM
cras::optional< double > getFocalLengthMM() override
movie_publisher::ExifBaseMetadataExtractor::getCropFactor
cras::optional< double > getCropFactor() override
movie_publisher::ExifBaseMetadataExtractor::getExifGpsAlt
virtual cras::optional< ExifData< ExifRational > > getExifGpsAlt()
Definition: ExifBaseMetadataExtractor.h:229
movie_publisher::ExifBaseMetadataExtractor::getRollPitch
cras::optional< std::pair< double, double > > getRollPitch() override


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