Go to the documentation of this file.
25 #include <sensor_msgs/Image.h>
96 const cras::optional<StreamTime>&
start,
const cras::optional<StreamTime>& end,
97 const cras::optional<StreamDuration>& duration);
105 virtual cras::expected<void, std::string>
setSubClip(
106 const cras::optional<StreamTime>&
start,
const cras::optional<StreamTime>& end,
107 const cras::optional<StreamDuration>& duration,
bool allowReopen);
127 virtual cras::expected<std::pair<MoviePlaybackState, sensor_msgs::ImageConstPtr>, std::string>
nextFrame();
142 virtual cras::expected<void, std::string>
seek(
const StreamTime& time,
bool allowReopen);
158 virtual cras::expected<void, std::string>
open();
164 virtual void close();
182 std::unique_ptr<MoviePrivate>
data;
cras::expected< void, std::string > seek(const StreamTime &time)
Seek the movie to the given time (relative to the start of the movie).
virtual cras::expected< std::pair< MoviePlaybackState, sensor_msgs::ImageConstPtr >, std::string > nextFrame()
Generator returning next frame of the movie on each call.
Configuration specifying what movie file to open and how.
MoviePlaybackState::Ptr _playbackState()
Custom movie_publisher datatypes.
Basic information about an open movie.
std::unique_ptr< MoviePrivate > data
PIMPL.
virtual void close()
Close the movie, free all acquired resources.
std::shared_ptr< Movie > MoviePtr
Time type denoting movie stream time.
Configuration specifying what movie file to open and how.
MovieOpenConfig & _config()
std::shared_ptr< MoviePlaybackState > Ptr
std::shared_ptr< const MovieInfo > ConstPtr
virtual cras::expected< void, std::string > seekInSubclip(const StreamTime &time)
Seek the movie to the given time (relative to the start of the subclip).
::cras::LogHelper::Ptr LogHelperPtr
virtual cras::expected< void, std::string > open()
Open the file configured in the config object passed to constructor.
An open movie that can be read, seeked and closed.
std::shared_ptr< const MoviePlaybackState > ConstPtr
std::shared_ptr< MovieInfo > Ptr
const MovieOpenConfig & config() const
virtual MetadataExtractor::Ptr staticMetadata() const
MoviePlaybackState::ConstPtr playbackState() const
Movie(const cras::LogHelperPtr &log, const MovieOpenConfig &config)
Open a movie in the referenced file.
std::shared_ptr< const Movie > MovieConstPtr
cras::expected< void, std::string > setSubClip(const cras::optional< StreamTime > &start, const cras::optional< StreamTime > &end, const cras::optional< StreamDuration > &duration)
Limit the part of the movie returned by nextFrame() calls to the given subclip.
MovieInfo::ConstPtr info() const
virtual void setTimestampOffset(const ros::Duration &offset)
Set the offset of the computed ROS timestamps relative to the reference time.
movie_publisher
Author(s): Martin Pecka
autogenerated on Wed May 28 2025 02:07:22