Skip to content

Commit

Permalink
compile tests
Browse files Browse the repository at this point in the history
Signed-off-by: Karsten Knese <karsten@openrobotics.org>
  • Loading branch information
Karsten1987 committed Apr 27, 2019
1 parent 1dcede7 commit f12e676
Show file tree
Hide file tree
Showing 4 changed files with 186 additions and 1 deletion.
23 changes: 22 additions & 1 deletion rosbag2_bag_v2_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,6 @@ ament_export_libraries(${PROJECT_NAME})
ament_export_dependencies(rosbag2_storage)
ament_export_dependencies(rosbag2 ros1_rosbag_storage rosbag2_storage)


if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_lint_auto REQUIRED)
Expand Down Expand Up @@ -158,6 +157,28 @@ if(BUILD_TESTING)
ament_target_dependencies(test_rosbag_output_stream
rosbag2_test_common)
endif()

ament_add_gmock(test_rosbag2_play_rosbag_v2_end_to_end
test/rosbag2_bag_v2_plugins/test_rosbag2_play_rosbag_v2_end_to_end.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_rosbag2_play_rosbag_v2_end_to_end)
ament_target_dependencies(test_rosbag2_play_rosbag_v2_end_to_end
rosbag2_storage
rclcpp
rosbag2_test_common
std_msgs)
endif()

ament_add_gmock(test_rosbag2_info_rosbag_v2_end_to_end
test/rosbag2_bag_v2_plugins/test_rosbag2_info_rosbag_v2_end_to_end.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_rosbag2_info_rosbag_v2_end_to_end)
ament_target_dependencies(test_rosbag2_info_rosbag_v2_end_to_end
rosbag2_storage
rclcpp
rosbag2_test_common
std_msgs)
endif()
endif()

ament_package()
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
// Copyright 2018, Bosch Software Innovations GmbH.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gmock/gmock.h>

#include <cstdlib>
#include <string>
#include <thread>

#include "rosbag2_test_common/process_execution_helpers.hpp"

using namespace ::testing; // NOLINT

class InfoV2EndToEndTestFixture : public Test
{
public:
InfoV2EndToEndTestFixture()
{
database_path_ = _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt
}

std::string database_path_;
};

TEST_F(InfoV2EndToEndTestFixture, info_end_to_end_test) {
internal::CaptureStdout();
auto exit_code = execute_and_wait_until_completion(
"ros2 bag info test_bag_end_to_end.bag -s rosbag_v2", database_path_);
std::string output = internal::GetCapturedStdout();

EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS));
// The bag size depends on the os and is not asserted, the time is asserted time zone independent
EXPECT_THAT(output, ContainsRegex(
"\nFiles: test_bag_end_to_end\\.bag"
"\nBag size: .*B"
"\nStorage id: rosbag_v2"
"\nDuration: 3\\.0s"
"\nStart: Dec .+ 2018 .+:.+:06\\.974 \\(1544000766\\.974\\)"
"\nEnd Dec .+ 2018 .+:.+:09\\.975 \\(1544000769\\.975\\)"
"\nMessages: 11"
"\nTopic information: "));

EXPECT_THAT(output, HasSubstr(
"Topic: rosout | Type: rosgraph_msgs/Log | Count: 5 | Serialization Format: rosbag_v2\n"));
EXPECT_THAT(output, HasSubstr("Topic: string_topic | Type: std_msgs/String | Count: 3 | "
"Serialization Format: rosbag_v2\n"));
EXPECT_THAT(output, HasSubstr(
"Topic: int_topic | Type: std_msgs/Int32 | Count: 3 | Serialization Format: rosbag_v2"
));
}


TEST_F(InfoV2EndToEndTestFixture, info_fails_gracefully_if_storage_format_is_not_specified) {
internal::CaptureStderr();
auto exit_code =
execute_and_wait_until_completion("ros2 bag info test_bag.bag", database_path_);
auto error_output = internal::GetCapturedStderr();

EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS));
EXPECT_THAT(error_output, HasSubstr("Could not read metadata for test_bag.bag"));
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
// Copyright 2018, Bosch Software Innovations GmbH.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gmock/gmock.h>

#include <cstdlib>
#include <future>
#include <iostream>
#include <map>
#include <memory>
#include <string>
#include <vector>

// rclcpp must be included before process_execution_helpers.hpp
#include "rclcpp/rclcpp.hpp"
#include "rosbag2_test_common/process_execution_helpers.hpp"

#include "std_msgs/msg/string.hpp"
#include "std_msgs/msg/int32.hpp"
#include "std_msgs/msg/int32_multi_array.hpp"
#include "rosbag2_test_common/subscription_manager.hpp"

using namespace ::testing; // NOLINT
using namespace rosbag2_test_common; // NOLINT

class PlayEndToEndTestFixture : public Test
{
public:
PlayEndToEndTestFixture()
{
database_path_ = _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt
sub_ = std::make_unique<SubscriptionManager>();
}

static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}

static void TearDownTestCase()
{
rclcpp::shutdown();
}

std::string database_path_;
std::unique_ptr<SubscriptionManager> sub_;
};

TEST_F(PlayEndToEndTestFixture, play_end_to_end_test_does_not_try_to_publish_ros1_topics) {
sub_->add_subscription<std_msgs::msg::String>("/string_topic", 2);
sub_->add_subscription<std_msgs::msg::Int32>("/int_topic", 2);

auto subscription_future = sub_->spin_subscriptions();

auto exit_code = execute_and_wait_until_completion(
"ros2 bag play test_bag_end_to_end.bag -s rosbag_v2", database_path_);

subscription_future.get();

auto string_messages = sub_->get_received_messages<std_msgs::msg::String>("/string_topic");
auto int_messages = sub_->get_received_messages<std_msgs::msg::Int32>("/int_topic");

EXPECT_THAT(string_messages, SizeIs(Ge(2u)));
EXPECT_THAT(string_messages[0]->data, StrEq("foo"));

EXPECT_THAT(int_messages, SizeIs(2));
EXPECT_THAT(int_messages[0]->data, Eq(42));

EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS));
}


TEST_F(PlayEndToEndTestFixture, play_fails_gracefully_if_rosbag_v2_storage_id_is_not_specified) {
internal::CaptureStderr();
auto exit_code =
execute_and_wait_until_completion("ros2 bag play test_bag.bag", database_path_);
auto error_output = internal::GetCapturedStderr();

EXPECT_THAT(exit_code, Eq(EXIT_SUCCESS));
EXPECT_THAT(error_output, HasSubstr("No storage could be initialized"));
}

0 comments on commit f12e676

Please sign in to comment.