Skip to content

Commit

Permalink
movie_publisher: Fixed buildfarm issues.
Browse files Browse the repository at this point in the history
  • Loading branch information
peci1 committed Jan 8, 2025
1 parent 44b80f5 commit 4d12b11
Show file tree
Hide file tree
Showing 8 changed files with 190 additions and 27 deletions.
5 changes: 0 additions & 5 deletions .github/ci.melodic.rosinstall
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,3 @@
local-name: compass
uri: https://github.com/ctu-vras/compass.git
version: master
# Fix https://github.com/ros/roslint/pull/90
- git:
local-name: roslint
uri: https://github.com/peci1/roslint.git
version: patch-2
5 changes: 0 additions & 5 deletions .github/ci.noetic.rosinstall
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,3 @@
local-name: ros-utils
uri: https://github.com/ctu-vras/ros-utils.git
version: master
# Fix https://github.com/ros/roslint/pull/90
- git:
local-name: roslint
uri: https://github.com/peci1/roslint.git
version: patch-2
9 changes: 6 additions & 3 deletions movie_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -73,11 +73,14 @@ add_executable(movie_to_bag_node nodes/movie_to_bag.cpp)
target_link_libraries(movie_to_bag_node movie_to_bag ${catkin_LIBRARIES})
set_target_properties(movie_to_bag_node PROPERTIES OUTPUT_NAME movie_to_bag PREFIX "")

add_executable(movies_to_bags nodes/movies_to_bags.cpp)
target_link_libraries(movies_to_bags PUBLIC movie_to_bag ${catkin_LIBRARIES} PRIVATE std::filesystem)

add_library(${PROJECT_NAME}_nodelet nodelets/${PROJECT_NAME}_nodelet.cpp)
target_link_libraries(${PROJECT_NAME}_nodelet PUBLIC movie_reader ${catkin_LIBRARIES})
cras_node_from_nodelet(${PROJECT_NAME}_nodelet ${PROJECT_NAME}::MoviePublisherNodelet OUTPUT_NAME ${PROJECT_NAME} ANONYMOUS)

install(TARGETS movie_to_bag_node
install(TARGETS movie_to_bag_node movies_to_bags
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Expand Down Expand Up @@ -128,13 +131,13 @@ if (CATKIN_ENABLE_TESTING)

roslaunch_add_file_check(launch/${PROJECT_NAME}.launch IGNORE_UNSET_ARGS)

catkin_add_gtest(test_movie_reader test/test_movie_reader.cpp)
catkin_add_gmock(test_movie_reader test/test_movie_reader.cpp)
target_link_libraries(test_movie_reader movie_reader movie_reader_metadata_plugins)
target_compile_definitions(test_movie_reader PRIVATE TEST_DATA_DIR="${CATKIN_DEVEL_PREFIX}/share/test_data")
add_custom_command(TARGET test_movie_reader POST_BUILD
COMMAND ${CMAKE_COMMAND} -E copy_directory "${CMAKE_CURRENT_SOURCE_DIR}/../test_data" "${CATKIN_DEVEL_PREFIX}/share/test_data")

add_rostest_gtest(test_${PROJECT_NAME}_nodelet test/test_${PROJECT_NAME}_nodelet.test test/test_${PROJECT_NAME}_nodelet.cpp)
add_rostest_gmock(test_${PROJECT_NAME}_nodelet test/test_${PROJECT_NAME}_nodelet.test test/test_${PROJECT_NAME}_nodelet.cpp)
target_link_libraries(test_${PROJECT_NAME}_nodelet ${catkin_LIBRARIES} ${PROJECT_NAME}_nodelet)
add_dependencies(test_${PROJECT_NAME}_nodelet test_movie_reader) # Wait for copying files
target_compile_definitions(test_${PROJECT_NAME}_nodelet PRIVATE TEST_DATA_DIR="${CATKIN_DEVEL_PREFIX}/share/test_data")
Expand Down
126 changes: 126 additions & 0 deletions movie_publisher/nodes/movies_to_bags.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
// SPDX-License-Identifier: BSD-3-Clause
// SPDX-FileCopyrightText: Czech Technical University in Prague

/**
* \file
* \brief Publisher of movie files to ROS image topics.
* \author Martin Pecka
*/

#include <memory>
#include <string>
#include <thread>

#include CXX_FILESYSTEM_INCLUDE
namespace fs = CXX_FILESYSTEM_NAMESPACE;

#include <compass_msgs/Azimuth.h>
#include <cras_cpp_common/functional.hpp>
#include <cras_cpp_common/node_utils.hpp>
#include <cras_cpp_common/node_utils/node_with_optional_master.h>
#include <cras_cpp_common/optional.hpp>
#include <cras_cpp_common/param_utils.hpp>
#include <gps_common/GPSFix.h>
#include <image_transport_codecs/image_transport_codecs.h>
#include <movie_publisher/movie_to_bag.h>
#include <nodelet/nodelet.h>
#include <pluginlib/class_list_macros.hpp>
#include <rosbag/bag.h>
#include <rosbag/view.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
#include <tf2_msgs/TFMessage.h>

namespace movie_publisher
{
/**
* \brief Convert movie files and their metadata to ROS bag file.
*
* \par 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}/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.
*
* 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.
*
* \par 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'`.
*
* - `~bag` (string, required): Path where the result should be stored.
* - `~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).
* - `~movie` (string, required): Path to the movie to play. Any format that ffmpeg can decode.
* - `~transport` (string, default `raw`, suggested `compressed`): The image_transport used to store the movie
* in the bag.
* - `~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).
*/
class MoviesToBags : public cras::NodeWithOptionalMaster
{
public:
explicit MoviesToBags(const cras::LogHelperPtr& log) : cras::NodeWithOptionalMaster(log)
{
}

// TODO

private:
};

}

int main(int argc, char* argv[])
{
const auto log = std::make_shared<cras::NodeLogHelper>();
movie_publisher::MoviesToBags node(log);

// We're using NodeWithOptionalMaster, so this is instead of ros::init().
const auto options = ros::init_options::AnonymousName;
node.init(argc, argv, "movies_to_bags", options);

const auto params = node.getPrivateParams();

return 0;
}

8 changes: 8 additions & 0 deletions movie_publisher/src/movie_reader_private.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,13 +14,21 @@
#include <regex>
#include <unordered_map>

#include <compass_msgs/Azimuth.h>
#include <cras_cpp_common/expected.hpp>
#include <cras_cpp_common/optional.hpp>
#include <cras_cpp_common/param_utils/bound_param_helper.hpp>
#include <geometry_msgs/TransformStamped.h>
#include <gps_common/GPSFix.h>
#include <movie_publisher/metadata_extractor.h>
#include <movie_publisher/metadata_manager.h>
#include <movie_publisher/movie_reader.h>
#include <ros/duration.h>
#include <ros/time.h>
#include <sensor_msgs/image_encodings.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
#include <tf2/LinearMath/Matrix3x3.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
Expand Down
1 change: 0 additions & 1 deletion movie_publisher/src/movie_to_bag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@

#include <memory>
#include <string>
#include <thread>

#include CXX_FILESYSTEM_INCLUDE
namespace fs = CXX_FILESYSTEM_NAMESPACE;
Expand Down
29 changes: 24 additions & 5 deletions movie_publisher/test/test_movie_publisher_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
*/

#include "gtest/gtest.h"
#include "gmock/gmock.h"

#include <cmath>
#include <map>
Expand Down Expand Up @@ -42,6 +43,24 @@ using FixDetail = gps_common::GPSFix;

ros::V_string my_argv;

constexpr uint32_t align(const uint32_t x, const uint32_t a)
{
return ((x) + (a) - 1) & ~((a) - 1);
}

testing::internal::AnyOfArrayMatcher<uint32_t> alignedStep(
const uint32_t width, const uint32_t channels, const uint32_t planes = 1)
{
const auto step = width * channels;
return testing::AnyOfArray({
planes * step,
planes * align(step, 8),
planes * align(step, 16),
planes * align(step, 32),
planes * align(step, 64),
});
}

template<typename NodeletType = cras::Nodelet>
std::unique_ptr<NodeletType> createNodelet(const cras::LogHelperPtr& log,
const ros::M_string& remaps = {},
Expand Down Expand Up @@ -137,7 +156,7 @@ TEST(MoviePublisherNodelet, FairphoneStill) // NOLINT
EXPECT_EQ(4000, lastImages[0].width);
EXPECT_EQ(3000, lastImages[0].height);
EXPECT_EQ(sensor_msgs::image_encodings::BGR8, lastImages[0].encoding);
EXPECT_EQ(12000, lastImages[0].step);
EXPECT_THAT(lastImages[0].step, alignedStep(4000, 3));
EXPECT_EQ(0, lastImages[0].is_bigendian);

EXPECT_EQ("test_optical_frame", lastCompressedImages[0].header.frame_id);
Expand Down Expand Up @@ -208,7 +227,7 @@ TEST(MoviePublisherNodelet, FairphoneMovie) // NOLINT
EXPECT_EQ(1080, lastImages[0].width);
EXPECT_EQ(1920, lastImages[0].height);
EXPECT_EQ(sensor_msgs::image_encodings::BGR8, lastImages[0].encoding);
EXPECT_EQ(3264, lastImages[0].step);
EXPECT_THAT(lastImages[0].step, alignedStep(1080, 3));
EXPECT_EQ(0, lastImages[0].is_bigendian);

EXPECT_EQ("test_optical_frame", lastCompressedImages[0].header.frame_id);
Expand All @@ -230,7 +249,7 @@ TEST(MoviePublisherNodelet, FairphoneMovie) // NOLINT
EXPECT_EQ(1080, lastImages[1].width);
EXPECT_EQ(1920, lastImages[1].height);
EXPECT_EQ(sensor_msgs::image_encodings::BGR8, lastImages[1].encoding);
EXPECT_EQ(3264, lastImages[1].step);
EXPECT_THAT(lastImages[0].step, alignedStep(1080, 3));
EXPECT_EQ(0, lastImages[1].is_bigendian);

EXPECT_EQ("test_optical_frame", lastCompressedImages[1].header.frame_id);
Expand Down Expand Up @@ -317,7 +336,7 @@ TEST(MoviePublisherNodelet, IphoneMovie) // NOLINT
EXPECT_EQ(1920, lastImages[0].width);
EXPECT_EQ(1080, lastImages[0].height);
EXPECT_EQ(sensor_msgs::image_encodings::BGR8, lastImages[0].encoding);
EXPECT_EQ(5760, lastImages[0].step);
EXPECT_THAT(lastImages[0].step, alignedStep(1920, 3));
EXPECT_EQ(0, lastImages[0].is_bigendian);

EXPECT_EQ("test_optical_frame", lastCompressedImages[0].header.frame_id);
Expand Down Expand Up @@ -360,7 +379,7 @@ TEST(MoviePublisherNodelet, IphoneMovie) // NOLINT
EXPECT_EQ(1920, lastImages[1].width);
EXPECT_EQ(1080, lastImages[1].height);
EXPECT_EQ(sensor_msgs::image_encodings::BGR8, lastImages[1].encoding);
EXPECT_EQ(5760, lastImages[1].step);
EXPECT_THAT(lastImages[0].step, alignedStep(1920, 3));
EXPECT_EQ(0, lastImages[1].is_bigendian);

EXPECT_EQ("test_optical_frame", lastCompressedImages[1].header.frame_id);
Expand Down
34 changes: 26 additions & 8 deletions movie_publisher/test/test_movie_reader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
*/

#include "gtest/gtest.h"
#include "gmock/gmock.h"

#include <list>
#include <memory>
Expand All @@ -32,6 +33,23 @@ using Az = compass_msgs::Azimuth;
using Imu = sensor_msgs::Imu;
using Fix = sensor_msgs::NavSatFix;

constexpr uint32_t align(const uint32_t x, const uint32_t a)
{
return ((x) + (a) - 1) & ~((a) - 1);
}

testing::internal::AnyOfArrayMatcher<uint32_t> alignedStep(
const uint32_t width, const uint32_t channels, const uint32_t planes = 1)
{
const auto step = width * channels;
return testing::AnyOfArray({
planes * step,
planes * align(step, 8),
planes * align(step, 16),
planes * align(step, 32),
planes * align(step, 64),
});
}

TEST(MovieReader, TestEncoding) // NOLINT
{
Expand Down Expand Up @@ -62,7 +80,7 @@ TEST(MovieReader, TestEncoding) // NOLINT
EXPECT_EQ(1920, image->height);
EXPECT_EQ("bgr8", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(3264, image->step);
EXPECT_THAT(image->step, alignedStep(1080, 3));
}

TEST(MovieReader, FairphoneStill) // NOLINT
Expand Down Expand Up @@ -100,7 +118,7 @@ TEST(MovieReader, FairphoneStill) // NOLINT
EXPECT_EQ(3000, image->height);
EXPECT_EQ("yuv422", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(8000, image->step);
EXPECT_THAT(image->step, alignedStep(4000, 1, 2));

maybeNextFrame = m.nextFrame();
ASSERT_TRUE(maybeNextFrame.has_value());
Expand Down Expand Up @@ -144,7 +162,7 @@ TEST(MovieReader, FairphoneMovie) // NOLINT
EXPECT_EQ(1920, image->height);
EXPECT_EQ("yuv422", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(2176, image->step);
EXPECT_THAT(image->step, alignedStep(1080, 1, 2));

maybeNextFrame = m.nextFrame();
ASSERT_TRUE(maybeNextFrame.has_value());
Expand Down Expand Up @@ -211,7 +229,7 @@ TEST(MovieReader, LumixStill) // NOLINT
EXPECT_EQ(3448, image->height);
EXPECT_EQ("yuv422", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(9184, image->step);
EXPECT_THAT(image->step, alignedStep(4592, 1, 2));

maybeNextFrame = m.nextFrame();
ASSERT_TRUE(maybeNextFrame.has_value());
Expand Down Expand Up @@ -252,7 +270,7 @@ TEST(MovieReader, LumixMovie) // NOLINT
EXPECT_EQ(1080, image->height);
EXPECT_EQ("yuv422", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(3840, image->step);
EXPECT_THAT(image->step, alignedStep(1920, 1, 2));

maybeNextFrame = m.nextFrame();
ASSERT_TRUE(maybeNextFrame.has_value());
Expand Down Expand Up @@ -320,7 +338,7 @@ TEST(MovieReader, FfmpegProcessed) // NOLINT
EXPECT_EQ(1080, image->height);
EXPECT_EQ("yuv422", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(3840, image->step);
EXPECT_THAT(image->step, alignedStep(1920, 1, 2));

maybeNextFrame = m.nextFrame();
ASSERT_TRUE(maybeNextFrame.has_value());
Expand Down Expand Up @@ -386,7 +404,7 @@ TEST(MovieReader, IphoneStill) // NOLINT
EXPECT_EQ(3024, image->height);
EXPECT_EQ("yuv422", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(8064, image->step);
EXPECT_THAT(image->step, alignedStep(4032, 1, 2));

maybeNextFrame = m.nextFrame();
ASSERT_TRUE(maybeNextFrame.has_value());
Expand Down Expand Up @@ -428,7 +446,7 @@ TEST(MovieReader, IphoneMovie) // NOLINT
EXPECT_EQ(1080, image->height);
EXPECT_EQ("yuv422", image->encoding);
EXPECT_EQ(false, image->is_bigendian);
EXPECT_EQ(3840, image->step);
EXPECT_THAT(image->step, alignedStep(1920, 1, 2));

maybeNextFrame = m.nextFrame();
ASSERT_TRUE(maybeNextFrame.has_value());
Expand Down

0 comments on commit 4d12b11

Please sign in to comment.