Go to the documentation of this file.
23 class MovieMetadataProcessor;
59 const std::vector<std::shared_ptr<MovieMetadataProcessor>>&
metadataProcessors()
const;
69 const std::vector<std::shared_ptr<MovieMetadataProcessor>>&
data);
116 cras::expected<void, std::string>
setFrameId(
const std::string&
data);
173 cras::expected<void, std::string>
setMetadataTypes(
const std::unordered_set<MetadataType>& types);
175 using Ptr = std::shared_ptr<MovieOpenConfig>;
176 using ConstPtr = std::shared_ptr<const MovieOpenConfig>;
180 std::unique_ptr<Impl>
data;
TimestampSource timestampSource() const
Configuration specifying what movie file to open and how.
cras::expected< void, std::string > setAllowYUVFallback(bool data)
std::unordered_set< MetadataType > metadataTypes() const
ros::Duration timestampOffset() const
::std::shared_ptr<::cras::BoundParamHelper > BoundParamHelperPtr
cras::expected< void, std::string > setTimestampSource(TimestampSource data)
cras::expected< void, std::string > setMetadataProcessors(const std::vector< std::shared_ptr< MovieMetadataProcessor >> &data)
cras::optional< int > forceStreamIndex() const
std::string filenameOrURL() const
cras::optional< std::string > forceEncoding() const
cras::expected< void, std::string > setForceStreamIndex(const cras::optional< int > &data)
TimestampSource
How to compute ROS timestamps from movie frame presentation timestamp (PTS).
cras::expected< void, std::string > setMetadataTypes(const std::unordered_set< MetadataType > &types)
cras::expected< void, std::string > setNumThreads(size_t data)
std::string frameId() const
size_t numThreads() const
cras::expected< void, std::string > setExtractMetadata(bool data)
MovieOpenConfig(const cras::BoundParamHelperPtr &rosParams)
cras::expected< void, std::string > setForceEncoding(const cras::optional< std::string > &data)
std::unique_ptr< Impl > data
PIMPL data.
std::string defaultEncoding() const
cras::expected< void, std::string > setDefaultEncoding(const std::string &data)
std::shared_ptr< MovieOpenConfig > Ptr
cras::expected< void, std::string > setTimestampOffset(const ros::Duration &data)
cras::expected< void, std::string > setFilenameOrURL(const std::string &data)
bool extractMetadata() const
std::shared_ptr< const MovieOpenConfig > ConstPtr
std::string opticalFrameId() const
cras::BoundParamHelperPtr rosParams() const
bool allowYUVFallback() const
cras::expected< void, std::string > setRosParams(const cras::BoundParamHelperPtr &data)
cras::expected< void, std::string > setOpticalFrameId(const std::string &data)
cras::expected< void, std::string > setFrameId(const std::string &data)
MovieOpenConfig & operator=(const MovieOpenConfig &other)
const std::vector< std::shared_ptr< MovieMetadataProcessor > > & metadataProcessors() const
movie_publisher
Author(s): Martin Pecka
autogenerated on Wed May 28 2025 02:07:22