movie_metadata_processor.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 
16 #include <geometry_msgs/TransformStamped.h>
17 #include <gps_common/GPSFix.h>
22 #include <sensor_msgs/CameraInfo.h>
23 #include <sensor_msgs/Image.h>
24 #include <sensor_msgs/Imu.h>
25 #include <sensor_msgs/MagneticField.h>
26 #include <sensor_msgs/NavSatFix.h>
27 #include <vision_msgs/Detection2DArray.h>
28 
29 namespace movie_publisher
30 {
45 {
46 public:
47  virtual ~MovieMetadataProcessor();
48 
55  virtual cras::expected<void, std::string> onOpen(const MovieInfo::ConstPtr& info, const MovieOpenConfig& config);
56 
62  virtual cras::expected<void, std::string> onMetadataReady(
63  const std::shared_ptr<TimedMetadataExtractor>& metadataExtractor);
64 
69  virtual cras::expected<void, std::string> onClose();
70 
76  virtual cras::expected<void, std::string> onSeek(const StreamTime& time) {return {};}
77 
84  virtual cras::expected<void, std::string> processFrame(
85  const sensor_msgs::ImageConstPtr& image, const MoviePlaybackState& playbackState);
86 
96  virtual cras::expected<void, std::string> processImage(
97  const sensor_msgs::ImageConstPtr& image, const cras::optional<sensor_msgs::CameraInfo>& cameraInfoMsg) {return {};}
98 
104  virtual cras::expected<void, std::string> processCameraInfo(const sensor_msgs::CameraInfo& cameraInfoMsg) {return {};}
105 
110  virtual cras::expected<void, std::string> processAzimuth(const compass_msgs::Azimuth& azimuthMsg) {return {};}
111 
116  virtual cras::expected<void, std::string> processNavSatFix(const sensor_msgs::NavSatFix& navSatFixMsg) {return {};}
117 
122  virtual cras::expected<void, std::string> processGps(const gps_common::GPSFix& gpsMsg) {return {};}
123 
128  virtual cras::expected<void, std::string> processImu(const sensor_msgs::Imu& imuMsg) {return {};}
129 
134  virtual cras::expected<void, std::string> processZeroRollPitchTf(
135  const geometry_msgs::TransformStamped& zeroRollPitchTfMsg) {return {};}
136 
141  virtual cras::expected<void, std::string> processOpticalTf(const geometry_msgs::TransformStamped& opticalTfMsg)
142  {
143  return {};
144  }
145 
150  virtual cras::expected<void, std::string> processMagneticField(const sensor_msgs::MagneticField& magneticFieldMsg)
151  {
152  return {};
153  }
154 
159  virtual cras::expected<void, std::string> processFaces(const vision_msgs::Detection2DArray& facesMsg) {return {};}
160 
161 protected:
163  cras::optional<MovieOpenConfig> config;
164  std::shared_ptr<MetadataExtractor> metadataExtractor;
165  bool verbose {false};
166 };
167 
168 }
movie_publisher::MovieMetadataProcessor::processImu
virtual cras::expected< void, std::string > processImu(const sensor_msgs::Imu &imuMsg)
Process the IMU message.
Definition: movie_metadata_processor.h:128
movie_publisher::MovieOpenConfig
Configuration specifying what movie file to open and how.
Definition: movie_open_config.h:28
movie_publisher::MovieMetadataProcessor::processCameraInfo
virtual cras::expected< void, std::string > processCameraInfo(const sensor_msgs::CameraInfo &cameraInfoMsg)
Process camera info.
Definition: movie_metadata_processor.h:104
movie_publisher::MovieMetadataProcessor::onMetadataReady
virtual cras::expected< void, std::string > onMetadataReady(const std::shared_ptr< TimedMetadataExtractor > &metadataExtractor)
Callback telling the processor that static metadata have been extracted and timed metadata are ready.
movie_publisher::MovieMetadataProcessor::processAzimuth
virtual cras::expected< void, std::string > processAzimuth(const compass_msgs::Azimuth &azimuthMsg)
Process the azimuth message.
Definition: movie_metadata_processor.h:110
movie_info.h
Basic information about an open movie.
movie_publisher::MovieMetadataProcessor::metadataExtractor
std::shared_ptr< MetadataExtractor > metadataExtractor
Accessor to static metadata of the last opened movie.
Definition: movie_metadata_processor.h:164
movie_publisher::MovieMetadataProcessor::processFaces
virtual cras::expected< void, std::string > processFaces(const vision_msgs::Detection2DArray &facesMsg)
Process the face detections message.
Definition: movie_metadata_processor.h:159
movie_publisher::MovieMetadataProcessor::processMagneticField
virtual cras::expected< void, std::string > processMagneticField(const sensor_msgs::MagneticField &magneticFieldMsg)
Process the magnetic field message.
Definition: movie_metadata_processor.h:150
movie_publisher::MoviePlaybackState
State of movie playback.
Definition: movie_playback_state.h:23
movie_publisher::MovieMetadataProcessor::onClose
virtual cras::expected< void, std::string > onClose()
Callback telling the processor that a movie has been closed.
movie_publisher::MovieMetadataProcessor::processGps
virtual cras::expected< void, std::string > processGps(const gps_common::GPSFix &gpsMsg)
Process the GPSFix message.
Definition: movie_metadata_processor.h:122
movie_publisher::MovieMetadataProcessor::~MovieMetadataProcessor
virtual ~MovieMetadataProcessor()
movie_publisher::MovieMetadataProcessor::processNavSatFix
virtual cras::expected< void, std::string > processNavSatFix(const sensor_msgs::NavSatFix &navSatFixMsg)
Process the NavSatFix message.
Definition: movie_metadata_processor.h:116
movie_playback_state.h
State of movie playback.
movie_publisher::MovieMetadataProcessor::processOpticalTf
virtual cras::expected< void, std::string > processOpticalTf(const geometry_msgs::TransformStamped &opticalTfMsg)
Process the optical frame TF message.
Definition: movie_metadata_processor.h:141
movie_publisher::MovieMetadataProcessor::info
MovieInfo::ConstPtr info
Information about the last opened movie.
Definition: movie_metadata_processor.h:162
movie_publisher::StreamTime
Time type denoting movie stream time.
Definition: types.h:115
movie_publisher::MovieMetadataProcessor::processFrame
virtual cras::expected< void, std::string > processFrame(const sensor_msgs::ImageConstPtr &image, const MoviePlaybackState &playbackState)
Process the frame read by MovieReader::nextFrame().
movie_open_config.h
Configuration specifying what movie file to open and how.
metadata_extractor.h
Extractor of image or movie metadata.
movie_publisher::MovieMetadataProcessor::processZeroRollPitchTf
virtual cras::expected< void, std::string > processZeroRollPitchTf(const geometry_msgs::TransformStamped &zeroRollPitchTfMsg)
Process the zero roll/pitch TF message.
Definition: movie_metadata_processor.h:134
movie_publisher::MovieMetadataProcessor::verbose
bool verbose
Whether the processor should be verbose.
Definition: movie_metadata_processor.h:165
movie_publisher::MovieInfo::ConstPtr
std::shared_ptr< const MovieInfo > ConstPtr
Definition: movie_info.h:195
movie_publisher::MovieMetadataProcessor::onSeek
virtual cras::expected< void, std::string > onSeek(const StreamTime &time)
Callback telling the processor that a movie has been seeked to the given time.
Definition: movie_metadata_processor.h:76
expected.hpp
movie_publisher
Definition: ExifBaseMetadataExtractor.h:27
movie_publisher::MovieMetadataProcessor::processImage
virtual cras::expected< void, std::string > processImage(const sensor_msgs::ImageConstPtr &image, const cras::optional< sensor_msgs::CameraInfo > &cameraInfoMsg)
Process the image and its camera info.
Definition: movie_metadata_processor.h:96
movie_publisher::MovieMetadataProcessor
Base for consumers of movie metadata.
Definition: movie_metadata_processor.h:44
movie_publisher::MovieMetadataProcessor::onOpen
virtual cras::expected< void, std::string > onOpen(const MovieInfo::ConstPtr &info, const MovieOpenConfig &config)
Callback telling the processor that a movie has been opened for reading.
movie_publisher::MovieMetadataProcessor::config
cras::optional< MovieOpenConfig > config
Configuration of the last opened movie.
Definition: movie_metadata_processor.h:163


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