#include <movie_to_bag.h>
Public Member Functions | |
virtual void | addTimestampOffsetVars (MovieReaderRos &reader) const |
void | close () |
MovieToBagMetadataProcessor (const cras::LogHelperPtr &log, const std::string &bagFilename, const std::string &transport, const std::function< std::string(const std::string &)> &resolveName, const cras::BoundParamHelperPtr ¶ms) | |
cras::expected< void, std::string > | processAzimuth (const compass_msgs::Azimuth &azimuthMsg) override |
Process the azimuth message. More... | |
cras::expected< void, std::string > | processFaces (const vision_msgs::Detection2DArray &facesMsg) override |
Process the face detections message. More... | |
cras::expected< void, std::string > | processGps (const gps_common::GPSFix &gpsMsg) override |
Process the GPSFix message. More... | |
cras::expected< void, std::string > | processImage (const sensor_msgs::ImageConstPtr &image, const cras::optional< sensor_msgs::CameraInfo > &cameraInfoMsg) override |
Process the image and its camera info. More... | |
cras::expected< void, std::string > | processImu (const sensor_msgs::Imu &imuMsg) override |
Process the IMU message. More... | |
cras::expected< void, std::string > | processMagneticField (const sensor_msgs::MagneticField &magneticFieldMsg) override |
Process the magnetic field message. More... | |
cras::expected< void, std::string > | processNavSatFix (const sensor_msgs::NavSatFix &navSatFixMsg) override |
Process the NavSatFix message. More... | |
cras::expected< void, std::string > | processOpticalTf (const geometry_msgs::TransformStamped &opticalTfMsg) override |
Process the optical frame TF message. More... | |
cras::expected< void, std::string > | processZeroRollPitchTf (const geometry_msgs::TransformStamped &zeroRollPitchTfMsg) override |
Process the zero roll/pitch TF message. More... | |
~MovieToBagMetadataProcessor () override | |
![]() | |
virtual cras::expected< void, std::string > | onClose () |
Callback telling the processor that a movie has been closed. More... | |
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. More... | |
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. More... | |
virtual cras::expected< void, std::string > | onSeek (const StreamTime &time) |
Callback telling the processor that a movie has been seeked to the given time. More... | |
virtual cras::expected< void, std::string > | processCameraInfo (const sensor_msgs::CameraInfo &cameraInfoMsg) |
Process camera info. More... | |
virtual cras::expected< void, std::string > | processFrame (const sensor_msgs::ImageConstPtr &image, const MoviePlaybackState &playbackState) |
Process the frame read by MovieReader::nextFrame(). More... | |
virtual | ~MovieMetadataProcessor () |
Protected Member Functions | |
virtual std::string | getAzimuthTopic () const |
virtual std::string | getCameraInfoTopic () const |
virtual std::string | getFacesTopic () const |
virtual std::string | getGpsTopic () const |
virtual std::string | getImageTopic () const |
virtual std::string | getImuTopic () const |
virtual std::string | getMagneticFieldTopic () const |
virtual std::string | getNavSatFixTopic () const |
virtual std::string | getPrefixedTopic (const std::string &topicName) const |
Prefix the given topic name with the base topic. More... | |
virtual std::string | getStaticTfTopic () const |
virtual std::string | getTfTopic () const |
![]() | |
::cras::LogHelperConstPtr | getCrasLogger () const |
HasLogger (const ::cras::LogHelperPtr &log) | |
void | setCrasLogger (const ::cras::LogHelperPtr &log) |
Protected Attributes | |
std::unique_ptr< rosbag::Bag > | bag |
The bag to write to. More... | |
std::unique_ptr< image_transport_codecs::ImageTransportCodecs > | imageCodecs |
Image transport codec instance. More... | |
cras::optional< geometry_msgs::TransformStamped > | lastOpticalTF |
Last optical transform. More... | |
std::function< std::string(const std::string &)> | resolveName |
std::string | topic |
The base topic name. More... | |
std::string | transport |
The transport to use. More... | |
![]() | |
cras::optional< MovieOpenConfig > | config |
Configuration of the last opened movie. More... | |
MovieInfo::ConstPtr | info |
Information about the last opened movie. More... | |
std::shared_ptr< MetadataExtractor > | metadataExtractor |
Accessor to static metadata of the last opened movie. More... | |
bool | verbose {false} |
Whether the processor should be verbose. More... | |
![]() | |
::cras::LogHelperPtr | log |
Definition at line 34 of file movie_to_bag.h.
|
explicit |
|
override |
|
virtual |
void movie_publisher::MovieToBagMetadataProcessor::close | ( | ) |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
Prefix the given topic name with the base topic.
[in] | topicName | Suffix to add to the base topic name. |
|
protectedvirtual |
|
protectedvirtual |
|
overridevirtual |
Process the azimuth message.
[in] | azimuthMsg | Azimuth message. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the face detections message.
[in] | facesMsg | Message with face detections. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the GPSFix message.
[in] | gpsMsg | GPSFix message. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the image and its camera info.
[in] | image | The decoded movie frame. |
[in] | cameraInfoMsg | The corresponding camera info (if present). |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the IMU message.
[in] | imuMsg | IMU message. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the magnetic field message.
[in] | magneticFieldMsg | Magnetic field message. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the NavSatFix message.
[in] | navSatFixMsg | NavSatFix message. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the optical frame TF message.
[in] | opticalTfMsg | Static TF message. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
overridevirtual |
Process the zero roll/pitch TF message.
[in] | zeroRollPitchTfMsg | Dynamic TF message. |
Reimplemented from movie_publisher::MovieMetadataProcessor.
|
protected |
The bag to write to.
Definition at line 78 of file movie_to_bag.h.
|
protected |
Image transport codec instance.
Definition at line 77 of file movie_to_bag.h.
|
protected |
Last optical transform.
Definition at line 82 of file movie_to_bag.h.
|
protected |
Definition at line 81 of file movie_to_bag.h.
|
protected |
The base topic name.
Definition at line 79 of file movie_to_bag.h.
|
protected |
The transport to use.
Definition at line 80 of file movie_to_bag.h.