Public Member Functions | Protected Member Functions | Private Attributes | List of all members
movie_publisher::Movie Class Reference

An open movie that can be read, seeked and closed. More...

#include <movie.h>

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

Public Member Functions

const MovieOpenConfigconfig () const
 
MovieInfo::ConstPtr info () const
 
 Movie (const cras::LogHelperPtr &log, const MovieOpenConfig &config)
 Open a movie in the referenced file. More...
 
virtual cras::expected< std::pair< MoviePlaybackState, sensor_msgs::ImageConstPtr >, std::string > nextFrame ()
 Generator returning next frame of the movie on each call. More...
 
MoviePlaybackState::ConstPtr playbackState () const
 
cras::expected< void, std::string > seek (const StreamTime &time)
 Seek the movie to the given time (relative to the start of the movie). More...
 
virtual cras::expected< void, std::string > seekInSubclip (const StreamTime &time)
 Seek the movie to the given time (relative to the start of the subclip). More...
 
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. More...
 
virtual void setTimestampOffset (const ros::Duration &offset)
 Set the offset of the computed ROS timestamps relative to the reference time. More...
 
virtual MetadataExtractor::Ptr staticMetadata () const
 
virtual ~Movie ()
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Protected Member Functions

MovieOpenConfig_config ()
 
MovieInfo::Ptr _info ()
 
MoviePlaybackState::Ptr _playbackState ()
 
virtual void close ()
 Close the movie, free all acquired resources. More...
 
virtual cras::expected< void, std::string > open ()
 Open the file configured in the config object passed to constructor. More...
 
virtual cras::expected< void, std::string > seek (const StreamTime &time, bool allowReopen)
 Seek the movie to the given time (relative to the start of the movie). More...
 
virtual cras::expected< void, std::string > setSubClip (const cras::optional< StreamTime > &start, const cras::optional< StreamTime > &end, const cras::optional< StreamDuration > &duration, bool allowReopen)
 Limit the part of the movie returned by nextFrame() calls to the given subclip. More...
 

Private Attributes

std::unique_ptr< MoviePrivatedata
 PIMPL. More...
 

Additional Inherited Members

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

Detailed Description

An open movie that can be read, seeked and closed.

Definition at line 35 of file movie.h.

Constructor & Destructor Documentation

◆ Movie()

movie_publisher::Movie::Movie ( const cras::LogHelperPtr log,
const MovieOpenConfig config 
)

Open a movie in the referenced file.

Parameters
[in]logcras_cpp_common logging helper.
[in]configThe configuration specifying what movie to open and how.
Exceptions
std::runtime_errorIf the movie cannot be opened.

◆ ~Movie()

virtual movie_publisher::Movie::~Movie ( )
virtual

Member Function Documentation

◆ _config()

MovieOpenConfig& movie_publisher::Movie::_config ( )
protected
Returns
The configuration with which the movie has been opened.

◆ _info()

MovieInfo::Ptr movie_publisher::Movie::_info ( )
protected
Returns
Basic information about the open movie.

◆ _playbackState()

MoviePlaybackState::Ptr movie_publisher::Movie::_playbackState ( )
protected
Returns
The current playback state (after the last call to nextFrame()).

◆ close()

virtual void movie_publisher::Movie::close ( )
protectedvirtual

Close the movie, free all acquired resources.

Note
This is automatically called in the destructor.

◆ config()

const MovieOpenConfig& movie_publisher::Movie::config ( ) const
Returns
The configuration with which the movie has been opened.

◆ info()

MovieInfo::ConstPtr movie_publisher::Movie::info ( ) const
Returns
Basic information about the open movie.

◆ nextFrame()

virtual cras::expected<std::pair<MoviePlaybackState, sensor_msgs::ImageConstPtr>, std::string> movie_publisher::Movie::nextFrame ( )
virtual

Generator returning next frame of the movie on each call.

On first call, this returns the first frame of the selected subclip. After seek(), this returns the first frame after the time it was seeked to.

Returns
The playback state and image. header.stamp of the image is the same as the rosTime of the playback state. It depends on what was set by setTimestampSource() and setTimestampOffset(). On error, an error message is returned. When a nullptr is returned for the image, the movie has reached its end and no more frames will be generated. This is also reflected in the playback state hasMovieEnded().

◆ open()

virtual cras::expected<void, std::string> movie_publisher::Movie::open ( )
protectedvirtual

Open the file configured in the config object passed to constructor.

Returns
Nothing or error.

◆ playbackState()

MoviePlaybackState::ConstPtr movie_publisher::Movie::playbackState ( ) const
Returns
The current playback state (after the last call to nextFrame()).

◆ seek() [1/2]

cras::expected<void, std::string> movie_publisher::Movie::seek ( const StreamTime time)

Seek the movie to the given time (relative to the start of the movie).

Parameters
[in]timeThe stream time to seek to. It is invalid to seek outside the selected subclip.
Returns
Nothing or an error if seek failed.
See also
seekInSubclip()

◆ seek() [2/2]

virtual cras::expected<void, std::string> movie_publisher::Movie::seek ( const StreamTime time,
bool  allowReopen 
)
protectedvirtual

Seek the movie to the given time (relative to the start of the movie).

Parameters
[in]timeThe stream time to seek to. It is invalid to seek outside the selected subclip.
Returns
Nothing or an error if seek failed.
See also
seekInSubclip()
Parameters
[in]allowReopenWhether it is allowed to reopen the movie (set to false to break recursion).

◆ seekInSubclip()

virtual cras::expected<void, std::string> movie_publisher::Movie::seekInSubclip ( const StreamTime time)
virtual

Seek the movie to the given time (relative to the start of the subclip).

Parameters
[in]timeThe subclip time to seek to. It is invalid to seek outside the selected subclip.
Returns
Nothing or an error if seek failed.
See also
seek()

◆ setSubClip() [1/2]

cras::expected<void, std::string> movie_publisher::Movie::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.

When all arguments are empty, the whole movie is played. If only start is non-empty, the movie plays from start to movie end. If only end is non-empty, the movie plays from the movie start to end. If only duration is non-empty, the movie plays from the movie start for duration seconds. If only start and duration are non-empty, the movie plays from start to start+duration. If only end and duration are non-empty, the movie plays from end-duration to duration. If only start and end are non-empty, the movie plays from start to end.

Error is returned when either:

  • all three arguments are non-empty
  • the movie is non-seekable and start or end-duration is non-zero
  • start or end are outside the movie timeline
  • duration is longer than the movie
  • start + duration is outside the movie timeline
  • end - duration is outside the movie timeline
  • end is before start
  • seek failed
Note
This function calls seek() if the current position in the whole movie does not fit in the new subclip. If you want to seek to the start of the subclip for sure, call seekInSubClip(0).
Parameters
[in]startThe start time (relative to movie start).
[in]endThe end time (relative to movie start).
[in]durationThe duration.
Returns
Nothing or error message.

◆ setSubClip() [2/2]

virtual cras::expected<void, std::string> movie_publisher::Movie::setSubClip ( const cras::optional< StreamTime > &  start,
const cras::optional< StreamTime > &  end,
const cras::optional< StreamDuration > &  duration,
bool  allowReopen 
)
protectedvirtual

Limit the part of the movie returned by nextFrame() calls to the given subclip.

Limit the part of the movie returned by nextFrame() calls to the given subclip. When all arguments are empty, the whole movie is played. If only start is non-empty, the movie plays from start to movie end. If only end is non-empty, the movie plays from the movie start to end. If only duration is non-empty, the movie plays from the movie start for duration seconds. If only start and duration are non-empty, the movie plays from start to start+duration. If only end and duration are non-empty, the movie plays from end-duration to duration. If only start and end are non-empty, the movie plays from start to end.

Error is returned when either:

  • all three arguments are non-empty
  • the movie is non-seekable and start or end-duration is non-zero
  • start or end are outside the movie timeline
  • duration is longer than the movie
  • start + duration is outside the movie timeline
  • end - duration is outside the movie timeline
  • end is before start
  • seek failed
Note
This function calls seek() if the current position in the whole movie does not fit in the new subclip. If you want to seek to the start of the subclip for sure, call seekInSubClip(0).
Parameters
[in]startThe start time (relative to movie start).
[in]endThe end time (relative to movie start).
[in]durationThe duration.
Returns
Nothing or error message.
Parameters
[in]allowReopenWhether it is allowed to reopen the movie (set to false to break recursion).

◆ setTimestampOffset()

virtual void movie_publisher::Movie::setTimestampOffset ( const ros::Duration offset)
virtual

Set the offset of the computed ROS timestamps relative to the reference time.

Parameters
[in]offsetThe offset.

◆ staticMetadata()

virtual MetadataExtractor::Ptr movie_publisher::Movie::staticMetadata ( ) const
virtual
Returns
The static metadata of the open movie.

Member Data Documentation

◆ data

std::unique_ptr<MoviePrivate> movie_publisher::Movie::data
private

PIMPL.

Definition at line 182 of file movie.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