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 e604352
Show file tree
Hide file tree
Showing 7 changed files with 60 additions and 26 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
4 changes: 2 additions & 2 deletions movie_publisher/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -128,13 +128,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
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 e604352

Please sign in to comment.