|
| MovieToBag (const cras::LogHelperPtr &log) |
|
virtual cras::expected< void, std::string > | open (const std::string &bagFilename, const std::string &transport, const std::string &movieFilename, const cras::BoundParamHelperPtr ¶ms) |
| Open the given movie file for reading and bag file for writing. More...
|
|
virtual cras::expected< void, std::string > | run () |
| Run the conversion. More...
|
|
::cras::BoundParamHelperPtr | getPrivateParams () const |
|
void | init (const ::ros::M_string &remappings, const ::std::string &name, uint32_t options) |
|
void | init (const ::ros::VP_string &remappings, const ::std::string &name, uint32_t options) |
|
void | init (int &argc, char **argv, const ::std::string &name, uint32_t options) |
|
bool | isInitialized () const |
|
| NodeWithOptionalMaster (const ::cras::LogHelperPtr &log) |
|
bool | ok () const |
|
::std::string | resolveName (const ::std::string &name, bool remap=true) const |
|
void | shutdown () |
|
bool | usesMaster () const |
|
virtual | ~NodeWithOptionalMaster () |
|
::cras::LogHelperConstPtr | getCrasLogger () const |
|
| HasLogger (const ::cras::LogHelperPtr &log) |
|
void | setCrasLogger (const ::cras::LogHelperPtr &log) |
|
Convert movie files and their metadata to ROS bag file.
- Stored topics
${~topic}
(sensor_msgs/Image
): The published movie (if raw transport is used).
${~topic}/${~transport}
(*): The published movie compressed stream (if raw transport is not used).
${~topic}/camera_info
(sensor_msgs/CameraInfo
): Camera info.
${~topic}/azimuth
(compass_msgs/Azimuth
): Georeferenced heading of the camera.
${~topic}/faces
(vision_msgs/Detection2DArray
): Faces detected in the image.
${~topic}/fix
(sensor_msgs/NavSatFix
): GNSS position of the camera.
${~topic}/fix_detail
(gps_common/GPSFix
): GNSS position of the camera.
${~topic}/imu
(sensor_msgs/Imu
): Orientation and acceleration of the camera.
${~topic}/mag
(sensor_msgs/MagneticField
): Magnetic field strength.
To extract the additional topics except movie
, the node uses instances of MetadataExtractor.
To change the prefix of all topics, set ~topic
parameter. To change the name of a single topic, remap it.
- Parameters
Parameters ~start
, ~end
and ~duration
can be expressed in seconds (15.35)
, in (min, sec)
, in (hour, min, sec)
, or as a string: ‘'01:03:05.35’`.
~overwrite_bag
(bool, default false): If true and the bag file exists, it will be overwritten. Otherwise, it will be appended (and created if needed).
~start
(float|tuple|string, optional): If set, the movie will be read from the specified time. Cannot be set together with ~end
and ~duration
.
~end
(float|tuple|string, optional): If set, the movie will be read up to the specified time (not affected by start). Cannot be set together with ~start
and ~duration
.
~duration
(float|tuple|string, optional): If set, playback will have this duration. If end is also set, the duration is counted from the end of the clip, otherwise, it is the duration from the start of the clip. Cannot be set together with ~start
and ~end
.
~timestamp_offset
(int|float|string, default 0.0): Adjustment of timestamps determined by ~timestamp_source
. If given as string, it can be a simple mathematical expression that can also resolve several variables: ros_time
(current ROS time), wall_time
(current wall time), metadata_start
(start time from metadata), bag_start
(start time of the bag file), bag_end
(end time of the metadata), bag_duration
(duration of the bag file in s).
~timestamp_source
(str, default metadata
): How to determine timestamps of the movie frames. Options are:
metadata
: Extract absolute time when the movie was recorded and use that time as timestamps.
all_zeros
: Use zero timestamps. Please note that time 0.0 cannot be stored in bag files. Use ~timestamp_offset
to make the time valid.
absolute_timecode
: Use the absolute timecode as timestamps (i.e. time since start of movie file).
relative_timecode
: Use the relative timecode as timestamps (i.e. time since ~start
).
ros_time
: Timestamp the frames with current ROS time. Note that this mode is not very useful for movie_to_bag.
~frame_id
(string, default ""): The frame_id used in the geometrical messages' headers.
~optical_frame_id
(string, default ${frame_id}_optical_frame
): The frame_id used in the image messages' headers.
~verbose
(bool, default False): If True, logs info about every frame played.
~allow_yuv_fallback
(bool, default False): Set whether YUV***
formats should be decoded to YUV422, or whether the default encoding should be used.
~default_encoding
(string, optional): Set the default encoding which should be used for output frames if there is no direct match between the libav pixel format and ROS image encodings.
~encoding
(string, optional): Set the encoding which should be used for output frames regardless of their source encoding (one of sensor_msgs::image_encodings constants).
Definition at line 146 of file movie_to_bag.h.