movie_private.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 <string>
13 #include <unordered_map>
14 
15 #include <compass_msgs/Azimuth.h>
19 #include <geometry_msgs/TransformStamped.h>
20 #include <gps_common/GPSFix.h>
22 #include <movie_publisher/movie.h>
24 #include <ros/duration.h>
25 #include <ros/time.h>
26 #include <sensor_msgs/CameraInfo.h>
27 #include <sensor_msgs/Imu.h>
28 #include <sensor_msgs/MagneticField.h>
29 #include <sensor_msgs/NavSatFix.h>
31 #include <vision_msgs/Detection2DArray.h>
32 
33 extern "C" {
34 #include <libavcodec/avcodec.h>
35 #include <libavfilter/avfilter.h>
36 #include <libavformat/avformat.h>
37 #include <libswscale/swscale.h>
38 }
39 
40 namespace movie_publisher
41 {
42 
43 #ifdef av_err2str
44 #undef av_err2str
45 av_always_inline char* av_err2str(const int errnum)
46 {
47  thread_local char str[AV_ERROR_MAX_STRING_SIZE] = {0};
48  return av_make_error_string(str, AV_ERROR_MAX_STRING_SIZE, errnum);
49 }
50 #endif
51 
52 // RAII helpers for libav
53 
55 {
56  void operator()(AVPacket* packet) noexcept { av_packet_unref(packet); }
57 };
58 using AVPacketPtr = std::unique_ptr<AVPacket, AVPacketClose>;
59 
61 {
62  void operator()(AVFrame* frame) noexcept { av_frame_unref(frame); }
63 };
64 using AVFramePtr = std::unique_ptr<AVFrame, AVFrameClose>;
65 
66 template <typename M>
67 M updateHeader(const M& msg, const ros::Time& stamp, const std::string& frameId)
68 {
69  M copy = msg;
70  copy.header.stamp = stamp;
71  copy.header.frame_id = frameId;
72  return copy;
73 }
74 
76 {
77 public:
79  void processGNSSPosition(const TimedMetadata<GNSSFixAndDetail>& gnss) override;
84  void processImu(const TimedMetadata<sensor_msgs::Imu>& data) override;
85  void processRollPitch(const TimedMetadata<std::pair<double, double>>& data) override;
87 
88 private:
89  template <typename M>
90  M fixHeader(const TimedMetadata<M>& msg, const std::string& frameId)
91  {
92  return updateHeader(msg.value, this->getTimestamp(msg.stamp), frameId);
93  }
94 
96  std::function<ros::Time(const StreamTime&)> getTimestamp;
97 };
98 
103 {
108  explicit MoviePrivate(const cras::LogHelperPtr& log);
109  ~MoviePrivate();
110 
114 
115  cras::optional<StreamTime> subclipStart;
116  cras::optional<StreamTime> subclipEnd;
117  cras::optional<StreamDuration> subclipDuration;
118 
119  // State variables
120  cras::optional<int64_t> seekRequest;
122 
123  // Extracted metadata
124  std::shared_ptr<MetadataManager> metadataManager;
125  std::shared_ptr<MovieMetadataListener> metadataListener;
126 
127  // Libav stuff
128  AVPixelFormat targetPixelFormat;
130  AVFilterGraph* filterGraph {};
131  AVFilterContext* filterBuffersrcContext {};
132  AVFilterContext* filterBuffersinkContext {};
133  SwsContext* swscaleContext {};
134  AVCodecContext* codecContext {};
135  AVStream* stream {};
136  AVFormatContext* formatContext {};
137 
141  bool isStillImage() const;
142 
146  bool isSeekable() const;
147 
152 
157 
161  StreamDuration getDuration() const;
162 
166  StreamTime getStreamStart() const;
167 
171  StreamTime getStreamEnd() const;
172 
177 
181  size_t getNumFrames() const;
182 
187 
191  void extractMetadata();
192 
197  void updateMetadata(const StreamTime& ptsTime);
198 
205  ros::Time getTimestamp(const StreamTime& ptsTime) const;
206 
211  cras::expected<std::pair<AVCodec*, int>, std::string> selectStream();
217  cras::expected<void, std::string> openCodec(const AVCodec* codec);
226  cras::expected<void, std::string> addRotationFilter();
231  cras::expected<void, std::string> configSwscale();
232 };
233 
234 }
movie_publisher::TimedMetadataListener
Listener of decoded timed metadata.
Definition: metadata_extractor.h:258
movie_publisher::MoviePrivate::getFrameRate
RationalNumber getFrameRate() const
optional.hpp
movie_publisher::AVFrameClose::operator()
void operator()(AVFrame *frame) noexcept
Definition: movie_private.h:62
movie_publisher::MovieOpenConfig
Configuration specifying what movie file to open and how.
Definition: movie_open_config.h:28
movie.h
An open movie.
movie_publisher::MovieMetadataListener::processGNSSPosition
void processGNSSPosition(const TimedMetadata< GNSSFixAndDetail > &gnss) override
Process the GNSS position of the camera when capturing the frame. \data[in] The GNSS position.
msg
msg
image_encodings.h
movie_publisher::MoviePrivate::filterBuffersinkContext
AVFilterContext * filterBuffersinkContext
Context for filter outputs.
Definition: movie_private.h:132
movie_publisher::MoviePrivate::isStillImage
bool isStillImage() const
movie_publisher::MoviePrivate::subclipEnd
cras::optional< StreamTime > subclipEnd
If nonempty, specifies the end of subclip to process.
Definition: movie_private.h:116
movie_publisher::MovieMetadataListener::config
MovieOpenConfig & config
Definition: movie_private.h:95
movie_publisher::MoviePrivate::extractMetadata
void extractMetadata()
Run metadata extractors to parse as much as possible in the *Msg members.
movie_publisher::MoviePrivate::detectTargetPixelFormat
void detectTargetPixelFormat()
Detect the pixel format into which we should extract images.
metadata_manager.h
Manager of multiple image metadata providers which can cooperate in parsing.
movie_publisher::TimedMetadata
Timestamping wrapper for any kind of metadata.
Definition: metadata_type.h:72
time.h
movie_publisher::MoviePrivate::prepareMetadataExtractors
void prepareMetadataExtractors()
Prepare metadata extractors.
cras::HasLogger
movie_publisher::MoviePrivate::lastSeek
StreamTime lastSeek
The value of the last seek request (0 before first seek).
Definition: movie_private.h:121
movie_publisher::MoviePrivate::metadataListener
std::shared_ptr< MovieMetadataListener > metadataListener
Listener to the extracted metadata.
Definition: movie_private.h:125
movie_publisher::MoviePrivate
PIMPL structure for Movie.
Definition: movie_private.h:102
movie_publisher::MoviePrivate::MoviePrivate
MoviePrivate(const cras::LogHelperPtr &log)
Constructor.
movie_publisher::MoviePrivate::getDuration
StreamDuration getDuration() const
movie_publisher::MoviePrivate::subclipStart
cras::optional< StreamTime > subclipStart
If nonempty, specifies the start of subclip to process.
Definition: movie_private.h:115
data
data
movie_publisher::MoviePrivate::getTimestamp
ros::Time getTimestamp(const StreamTime &ptsTime) const
Compute ROS timestamp corresponding to the given stream timestamp taking into account the configured ...
movie_publisher::StreamTime
Time type denoting movie stream time.
Definition: types.h:115
movie_publisher::MoviePrivate::playbackState
MoviePlaybackState::Ptr playbackState
Playback state of the movie.
Definition: movie_private.h:113
movie_publisher::MovieMetadataListener::processRollPitch
void processRollPitch(const TimedMetadata< std::pair< double, double >> &data) override
duration.h
movie_publisher::MoviePrivate::info
MovieInfo::Ptr info
Definition: movie_private.h:112
movie_publisher::MoviePrivate::stream
AVStream * stream
The selected stream.
Definition: movie_private.h:135
movie_publisher::AVFrameClose
Definition: movie_private.h:60
frameId
std::string const * frameId(const M &m)
movie_publisher::MovieMetadataListener::processMagneticField
void processMagneticField(const TimedMetadata< sensor_msgs::MagneticField > &data) override
Process the magnetic field acting on the camera. \data[in] The magnetic field measurement in X,...
movie_publisher::MovieMetadataListener::processCameraInfo
void processCameraInfo(const TimedMetadata< sensor_msgs::CameraInfo > &data) override
Process camera info. \data[in] Camera info data.
movie_publisher::MoviePrivate::getStreamDuration
StreamDuration getStreamDuration() const
movie_publisher::MoviePrivate::imageBufferSize
int imageBufferSize
Size of the image buffer.
Definition: movie_private.h:129
movie_publisher::MovieMetadataListener::processFaces
void processFaces(const TimedMetadata< vision_msgs::Detection2DArray > &data) override
Process faces detected in the scene. \data[in] The faces that were detected.
movie_publisher::MoviePrivate::isSeekable
bool isSeekable() const
movie_publisher::MovieMetadataListener::fixHeader
M fixHeader(const TimedMetadata< M > &msg, const std::string &frameId)
Definition: movie_private.h:90
movie_publisher::MoviePrivate::swscaleContext
SwsContext * swscaleContext
Scaling context.
Definition: movie_private.h:133
movie_publisher::MoviePrivate::~MoviePrivate
~MoviePrivate()
movie_publisher::MoviePrivate::filterBuffersrcContext
AVFilterContext * filterBuffersrcContext
Context for filter inputs.
Definition: movie_private.h:131
movie_publisher::MoviePrivate::config
MovieOpenConfig::Ptr config
Definition: movie_private.h:111
bound_param_helper.hpp
movie_publisher::MoviePrivate::codecContext
AVCodecContext * codecContext
Codec context.
Definition: movie_private.h:134
movie_publisher::MovieMetadataListener::processOpticalFrameTF
void processOpticalFrameTF(const TimedMetadata< geometry_msgs::Transform > &data) override
Process the optical frame transform (might be affected by image rotation). \data[in] Transform betwee...
movie_publisher::MovieMetadataListener::MovieMetadataListener
MovieMetadataListener(MovieOpenConfig &config, const std::function< ros::Time(const StreamTime &)> &getTimestamp)
movie_publisher::MoviePrivate::targetPixelFormat
AVPixelFormat targetPixelFormat
The desired output pixel format.
Definition: movie_private.h:128
movie_publisher::MoviePrivate::addRotationFilter
cras::expected< void, std::string > addRotationFilter()
Add an image rotation filter to the libav graph so that the outputs are upright.
movie_publisher::MoviePlaybackState::Ptr
std::shared_ptr< MoviePlaybackState > Ptr
Definition: movie_playback_state.h:100
movie_publisher::MovieOpenConfig::Ptr
std::shared_ptr< MovieOpenConfig > Ptr
Definition: movie_open_config.h:175
movie_publisher::MoviePrivate::subclipDuration
cras::optional< StreamDuration > subclipDuration
If nonempty, specifies the duration of subclip to process.
Definition: movie_private.h:117
expected.hpp
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
movie_publisher::MovieMetadataListener::processImu
void processImu(const TimedMetadata< sensor_msgs::Imu > &data) override
Process IMU data. \data[in] IMU data.
movie_publisher::AVPacketClose
Definition: movie_private.h:54
ros::Time
movie_publisher::AVFramePtr
std::unique_ptr< AVFrame, AVFrameClose > AVFramePtr
Definition: movie_private.h:64
movie_publisher::MoviePrivate::formatContext
AVFormatContext * formatContext
Format context.
Definition: movie_private.h:136
movie_publisher::MoviePrivate::getStreamStart
StreamTime getStreamStart() const
movie_publisher
Definition: ExifBaseMetadataExtractor.h:27
movie_publisher::MovieMetadataListener::getTimestamp
std::function< ros::Time(const StreamTime &)> getTimestamp
Definition: movie_private.h:96
movie_publisher::MoviePrivate::openCodec
cras::expected< void, std::string > openCodec(const AVCodec *codec)
Open the given codec for decoding.
movie_publisher::MoviePrivate::seekRequest
cras::optional< int64_t > seekRequest
When set, the next returned frame should be seeked to this position.
Definition: movie_private.h:120
movie_publisher::MovieMetadataListener
Definition: movie_private.h:75
movie_publisher::MoviePrivate::metadataManager
std::shared_ptr< MetadataManager > metadataManager
Manager of the extractable metadata.
Definition: movie_private.h:124
movie_publisher::AVPacketClose::operator()
void operator()(AVPacket *packet) noexcept
Definition: movie_private.h:56
movie_publisher::MovieMetadataListener::processAzimuth
void processAzimuth(const TimedMetadata< compass_msgs::Azimuth > &data) override
Process the azimuth describing global camera heading when capturing the frame. \data[in] The azimuth.
movie_publisher::MovieInfo::Ptr
std::shared_ptr< MovieInfo > Ptr
Definition: movie_info.h:194
movie_publisher::MoviePrivate::getContainerDuration
StreamDuration getContainerDuration() const
cras::HasLogger::log
::cras::LogHelperPtr log
movie_reader.h
Read a movie or image file.
movie_publisher::MoviePrivate::getStreamEnd
StreamTime getStreamEnd() const
movie_publisher::RationalNumber
A simple representation of rational numbers of the form numerator/denominator.
Definition: types.h:24
movie_publisher::MoviePrivate::configSwscale
cras::expected< void, std::string > configSwscale()
Add a scaling filter to the libav graph so that the outputs are properly scaled and color-transformed...
movie_publisher::StreamDuration
Duration type denoting movie stream duration.
Definition: types.h:44
movie_publisher::MoviePrivate::filterGraph
AVFilterGraph * filterGraph
Filter graph for decoding effects.
Definition: movie_private.h:130
movie_publisher::MoviePrivate::getNumFrames
size_t getNumFrames() const
movie_publisher::AVPacketPtr
std::unique_ptr< AVPacket, AVPacketClose > AVPacketPtr
Definition: movie_private.h:58
movie_publisher::updateHeader
M updateHeader(const M &msg, const ros::Time &stamp, const std::string &frameId)
Definition: movie_private.h:67
movie_publisher::MoviePrivate::selectStream
cras::expected< std::pair< AVCodec *, int >, std::string > selectStream()
Select the best quality stream and open it for decoding.
movie_publisher::MoviePrivate::updateMetadata
void updateMetadata(const StreamTime &ptsTime)
Update the metadata for another frame (if some metadata are time-dependent).


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