Public Types | Public Member Functions | Private Member Functions | List of all members
movie_publisher::MetadataExtractor Class Referenceabstract

Extractor of metadata about a movie or image. More...

#include <metadata_extractor.h>

Inheritance diagram for movie_publisher::MetadataExtractor:
Inheritance graph
[legend]

Public Types

using ConstPtr = std::shared_ptr< const MetadataExtractor >
 
using Ptr = std::shared_ptr< MetadataExtractor >
 

Public Member Functions

virtual cras::optional< geometry_msgs::Vector3 > getAcceleration ()
 
virtual cras::optional< geometry_msgs::Vector3 > getAngularVelocity ()
 
virtual cras::optional< compass_msgs::Azimuth > getAzimuth ()
 
virtual cras::optional< std::string > getCameraGeneralName ()
 
virtual cras::optional< sensor_msgs::CameraInfo > getCameraInfo ()
 
virtual cras::optional< std::string > getCameraMake ()
 
virtual cras::optional< std::string > getCameraModel ()
 
virtual cras::optional< std::string > getCameraSerialNumber ()
 
virtual cras::optional< std::string > getCameraUniqueName ()
 
virtual cras::optional< ros::TimegetCreationTime ()
 
virtual cras::optional< double > getCropFactor ()
 
virtual cras::optional< DistortionDatagetDistortion ()
 
virtual cras::optional< vision_msgs::Detection2DArray > getFaces ()
 
virtual cras::optional< double > getFocalLength35MM ()
 
virtual cras::optional< double > getFocalLengthMM ()
 
virtual cras::optional< double > getFocalLengthPx ()
 
virtual GNSSFixAndDetail getGNSSPosition ()
 
virtual cras::optional< sensor_msgs::Imu > getImu ()
 
virtual cras::optional< IntrinsicMatrixgetIntrinsicMatrix ()
 
virtual cras::optional< std::string > getLensMake ()
 
virtual cras::optional< std::string > getLensModel ()
 
virtual cras::optional< sensor_msgs::MagneticField > getMagneticField ()
 
virtual std::string getName () const =0
 Return the name of the extractor. More...
 
virtual cras::optional< geometry_msgs::Transform > getOpticalFrameTF ()
 
virtual int getPriority () const =0
 Return the priority of the extractor (for ordering in MetadataManager). More...
 
virtual cras::optional< RollPitchgetRollPitch ()
 
virtual cras::optional< intgetRotation ()
 
virtual cras::optional< SensorSizegetSensorSizeMM ()
 
virtual cras::optional< geometry_msgs::Transform > getZeroRollPitchTF ()
 
 MetadataExtractor (const cras::LogHelperPtr &log)
 Constructor. More...
 
virtual void processPacket (const AVPacket *packet)
 Optional processing of libav packets as they are read from the movie file. More...
 
virtual ~MetadataExtractor ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Private Member Functions

virtual void __reserved0 ()
 
virtual void __reserved1 ()
 
virtual void __reserved2 ()
 
virtual void __reserved3 ()
 
virtual void __reserved4 ()
 
virtual void __reserved5 ()
 
virtual void __reserved6 ()
 
virtual void __reserved7 ()
 
virtual void __reserved8 ()
 
virtual void __reserved9 ()
 

Additional Inherited Members

- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Detailed Description

Extractor of metadata about a movie or image.

The extractors implementing this interface should only override methods in case they can directly provide the data. If some data cannot be provided by an extractor, it is not a problem - MetadataManager will call other extractors to get the information.

If this extractor needs some metadata it cannot get itself, it can store a pointer to the manager and then call the manager to ask other extractors for the needed data. In this case, use StackGuard to protect against infinite recursion.

Some metadata reference transformation frames. Two frames are recognized:

Note
Implementing classes should not call any of the base implementations provided by this class.

Definition at line 76 of file metadata_extractor.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 80 of file metadata_extractor.h.

◆ Ptr

Definition at line 79 of file metadata_extractor.h.

Constructor & Destructor Documentation

◆ MetadataExtractor()

movie_publisher::MetadataExtractor::MetadataExtractor ( const cras::LogHelperPtr log)
explicit

Constructor.

Parameters
[in]logLogger.

◆ ~MetadataExtractor()

virtual movie_publisher::MetadataExtractor::~MetadataExtractor ( )
virtual

Member Function Documentation

◆ __reserved0()

virtual void movie_publisher::MetadataExtractor::__reserved0 ( )
inlineprivatevirtual

Definition at line 230 of file metadata_extractor.h.

◆ __reserved1()

virtual void movie_publisher::MetadataExtractor::__reserved1 ( )
inlineprivatevirtual

Definition at line 231 of file metadata_extractor.h.

◆ __reserved2()

virtual void movie_publisher::MetadataExtractor::__reserved2 ( )
inlineprivatevirtual

Definition at line 232 of file metadata_extractor.h.

◆ __reserved3()

virtual void movie_publisher::MetadataExtractor::__reserved3 ( )
inlineprivatevirtual

Definition at line 233 of file metadata_extractor.h.

◆ __reserved4()

virtual void movie_publisher::MetadataExtractor::__reserved4 ( )
inlineprivatevirtual

Definition at line 234 of file metadata_extractor.h.

◆ __reserved5()

virtual void movie_publisher::MetadataExtractor::__reserved5 ( )
inlineprivatevirtual

Definition at line 235 of file metadata_extractor.h.

◆ __reserved6()

virtual void movie_publisher::MetadataExtractor::__reserved6 ( )
inlineprivatevirtual

Definition at line 236 of file metadata_extractor.h.

◆ __reserved7()

virtual void movie_publisher::MetadataExtractor::__reserved7 ( )
inlineprivatevirtual

Definition at line 237 of file metadata_extractor.h.

◆ __reserved8()

virtual void movie_publisher::MetadataExtractor::__reserved8 ( )
inlineprivatevirtual

Definition at line 238 of file metadata_extractor.h.

◆ __reserved9()

virtual void movie_publisher::MetadataExtractor::__reserved9 ( )
inlineprivatevirtual

Definition at line 239 of file metadata_extractor.h.

◆ getAcceleration()

virtual cras::optional<geometry_msgs::Vector3> movie_publisher::MetadataExtractor::getAcceleration ( )
inlinevirtual
Returns
Acceleration vector acting on the camera when capturing the frame (including gravity) [m/s^2].

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 192 of file metadata_extractor.h.

◆ getAngularVelocity()

virtual cras::optional<geometry_msgs::Vector3> movie_publisher::MetadataExtractor::getAngularVelocity ( )
inlinevirtual
Returns
Angular velocity acting on the camera when capturing the frame. [rad/s].

Reimplemented in movie_publisher::MetadataManager.

Definition at line 196 of file metadata_extractor.h.

◆ getAzimuth()

virtual cras::optional<compass_msgs::Azimuth> movie_publisher::MetadataExtractor::getAzimuth ( )
inlinevirtual
Returns
Azimuth describing global camera heading when capturing the frame. Timestamp is zero.

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 180 of file metadata_extractor.h.

◆ getCameraGeneralName()

virtual cras::optional<std::string> movie_publisher::MetadataExtractor::getCameraGeneralName ( )
inlinevirtual
Returns
String describing the complete camera model.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 111 of file metadata_extractor.h.

◆ getCameraInfo()

virtual cras::optional<sensor_msgs::CameraInfo> movie_publisher::MetadataExtractor::getCameraInfo ( )
inlinevirtual
Returns
Extracted camera info combined from other fields, or nothing. Timestamp is zero.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 205 of file metadata_extractor.h.

◆ getCameraMake()

virtual cras::optional<std::string> movie_publisher::MetadataExtractor::getCameraMake ( )
inlinevirtual

◆ getCameraModel()

virtual cras::optional<std::string> movie_publisher::MetadataExtractor::getCameraModel ( )
inlinevirtual
Returns
The camera model name (just the model, without manufacturer).

Reimplemented in movie_publisher::MetadataManager, movie_publisher::ExifBaseMetadataExtractor, and movie_publisher::LibavStreamMetadataExtractor.

Definition at line 128 of file metadata_extractor.h.

◆ getCameraSerialNumber()

virtual cras::optional<std::string> movie_publisher::MetadataExtractor::getCameraSerialNumber ( )
inlinevirtual
Returns
The camera's serial number.

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 120 of file metadata_extractor.h.

◆ getCameraUniqueName()

virtual cras::optional<std::string> movie_publisher::MetadataExtractor::getCameraUniqueName ( )
inlinevirtual
Returns
String describing the camera in a unique way, utilizing serial numbers etc. If unique identification is not possible, nothing is returned.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 116 of file metadata_extractor.h.

◆ getCreationTime()

virtual cras::optional<ros::Time> movie_publisher::MetadataExtractor::getCreationTime ( )
inlinevirtual

◆ getCropFactor()

virtual cras::optional<double> movie_publisher::MetadataExtractor::getCropFactor ( )
inlinevirtual
Returns
Crop factor of the camera (i.e. how many times is the sensing area smaller than 36x24 mm).

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 148 of file metadata_extractor.h.

◆ getDistortion()

virtual cras::optional<DistortionData> movie_publisher::MetadataExtractor::getDistortion ( )
inlinevirtual
Returns
Camera distortion coefficients (corresponding to the OpenCV calibration model: 5 or 8 elements).

Reimplemented in movie_publisher::MetadataManager.

Definition at line 172 of file metadata_extractor.h.

◆ getFaces()

virtual cras::optional<vision_msgs::Detection2DArray> movie_publisher::MetadataExtractor::getFaces ( )
inlinevirtual
Returns
Faces detected in the scene. Timestamps are zero.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 200 of file metadata_extractor.h.

◆ getFocalLength35MM()

virtual cras::optional<double> movie_publisher::MetadataExtractor::getFocalLength35MM ( )
inlinevirtual
Returns
Focal length recomputed to an equivalent 35 mm system.

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 156 of file metadata_extractor.h.

◆ getFocalLengthMM()

virtual cras::optional<double> movie_publisher::MetadataExtractor::getFocalLengthMM ( )
inlinevirtual
Returns
The focal length in mm.

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 160 of file metadata_extractor.h.

◆ getFocalLengthPx()

virtual cras::optional<double> movie_publisher::MetadataExtractor::getFocalLengthPx ( )
inlinevirtual
Returns
The focal length in pixels.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 164 of file metadata_extractor.h.

◆ getGNSSPosition()

virtual GNSSFixAndDetail movie_publisher::MetadataExtractor::getGNSSPosition ( )
inlinevirtual
Returns
GNSS position of the camera when capturing the frame. Timestamps are zero.

Reimplemented in movie_publisher::MetadataManager, movie_publisher::ExifBaseMetadataExtractor, and movie_publisher::LibavStreamMetadataExtractor.

Definition at line 176 of file metadata_extractor.h.

◆ getImu()

virtual cras::optional<sensor_msgs::Imu> movie_publisher::MetadataExtractor::getImu ( )
inlinevirtual
Returns
Extracted IMU info combined from other fields, or nothing. Timestamp is zero.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 210 of file metadata_extractor.h.

◆ getIntrinsicMatrix()

virtual cras::optional<IntrinsicMatrix> movie_publisher::MetadataExtractor::getIntrinsicMatrix ( )
inlinevirtual
Returns
The intrinsic calibration matrix of the camera.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 168 of file metadata_extractor.h.

◆ getLensMake()

virtual cras::optional<std::string> movie_publisher::MetadataExtractor::getLensMake ( )
inlinevirtual
Returns
Lens manufacturer.

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 132 of file metadata_extractor.h.

◆ getLensModel()

virtual cras::optional<std::string> movie_publisher::MetadataExtractor::getLensModel ( )
inlinevirtual
Returns
Lens model.

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 136 of file metadata_extractor.h.

◆ getMagneticField()

virtual cras::optional<sensor_msgs::MagneticField> movie_publisher::MetadataExtractor::getMagneticField ( )
inlinevirtual
Returns
The magnetic field acting on the camera; measurement in X, Y and Z axes [T]. Timestamp is zero.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 184 of file metadata_extractor.h.

◆ getName()

virtual std::string movie_publisher::MetadataExtractor::getName ( ) const
pure virtual

◆ getOpticalFrameTF()

virtual cras::optional<geometry_msgs::Transform> movie_publisher::MetadataExtractor::getOpticalFrameTF ( )
inlinevirtual
Returns
Optical frame transform, i.e. transform between camera's geometrical and optical frame. It might be affected by image rotation.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 216 of file metadata_extractor.h.

◆ getPriority()

virtual int movie_publisher::MetadataExtractor::getPriority ( ) const
pure virtual

Return the priority of the extractor (for ordering in MetadataManager).

Returns
The priority. Lower values have more priority. Usually between 0 and 100.

Implemented in movie_publisher::MetadataManager, movie_publisher::LibavStreamMetadataExtractor, movie_publisher::FileMetadataExtractor, and movie_publisher::FilenameMetadataExtractor.

◆ getRollPitch()

virtual cras::optional<RollPitch> movie_publisher::MetadataExtractor::getRollPitch ( )
inlinevirtual
Returns
Gravity-aligned roll and pitch of the camera when capturing the frame [rad].

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 188 of file metadata_extractor.h.

◆ getRotation()

virtual cras::optional<int> movie_publisher::MetadataExtractor::getRotation ( )
inlinevirtual
Returns
Rotation of the image in degrees. Only values 0, 90, 180 and 270 are supported.

Reimplemented in movie_publisher::MetadataManager, movie_publisher::ExifBaseMetadataExtractor, and movie_publisher::LibavStreamMetadataExtractor.

Definition at line 140 of file metadata_extractor.h.

◆ getSensorSizeMM()

virtual cras::optional<SensorSize> movie_publisher::MetadataExtractor::getSensorSizeMM ( )
inlinevirtual
Returns
Physical size of the active sensor area that captures the movie (in mm; width, height).

Reimplemented in movie_publisher::MetadataManager, and movie_publisher::ExifBaseMetadataExtractor.

Definition at line 152 of file metadata_extractor.h.

◆ getZeroRollPitchTF()

virtual cras::optional<geometry_msgs::Transform> movie_publisher::MetadataExtractor::getZeroRollPitchTF ( )
inlinevirtual
Returns
The transform from camera body frame to a gravity-aligned frame.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 221 of file metadata_extractor.h.

◆ processPacket()

virtual void movie_publisher::MetadataExtractor::processPacket ( const AVPacket *  packet)
inlinevirtual

Optional processing of libav packets as they are read from the movie file.

Parameters
[in]packetThe libav packet.
Note
av_packet_ref() the packet if you want to store it for longer than this call duration.

Reimplemented in movie_publisher::MetadataManager.

Definition at line 106 of file metadata_extractor.h.


The documentation for this class was generated from the following file:


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