Skip to content

Commit

Permalink
Test for lifecycle manager (#1794)
Browse files Browse the repository at this point in the history
* Add test

* Add more coverage

* Merge test header file with executable

* Address PR reviewer's comment

* Add some more coverage

* Revert accidental changes to localization_launch.py file.
  • Loading branch information
shivaang12 committed Jun 5, 2020
1 parent d1240c2 commit 9e304b1
Show file tree
Hide file tree
Showing 4 changed files with 208 additions and 0 deletions.
5 changes: 5 additions & 0 deletions nav2_lifecycle_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,11 @@ install(DIRECTORY include/ DESTINATION include/)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()

find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_pytest REQUIRED)

add_subdirectory(test)
endif()

ament_export_include_directories(include)
Expand Down
20 changes: 20 additions & 0 deletions nav2_lifecycle_manager/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
ament_add_gtest_executable(test_lifecycle_gtest
test_lifecycle_manager.cpp
)

target_link_libraries(test_lifecycle_gtest
${library_name}
)

ament_target_dependencies(test_lifecycle_gtest
${dependencies}
)

ament_add_test(test_lifecycle
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/launch_lifecycle_test.py"
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
TIMEOUT 180
ENV
TEST_EXECUTABLE=$<TARGET_FILE:test_lifecycle_gtest>
)
57 changes: 57 additions & 0 deletions nav2_lifecycle_manager/test/launch_lifecycle_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
#! /usr/bin/env python3
# Copyright (c) 2020 Shivang Patel
#
# 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.

import os
import sys

from launch import LaunchDescription
from launch import LaunchService
from launch.actions import ExecuteProcess
from launch_ros.actions import Node
from launch_testing.legacy import LaunchTestService


def generate_launch_description():
return LaunchDescription([
Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager_test',
output='screen',
parameters=[{'use_sim_time': False},
{'autostart': False},
{'node_names': ['lifecycle_node_test']}]),
])


def main(argv=sys.argv[1:]):
ld = generate_launch_description()

testExecutable = os.getenv('TEST_EXECUTABLE')

test1_action = ExecuteProcess(
cmd=[testExecutable],
name='test_lifecycle_node_gtest',
output='screen')

lts = LaunchTestService()
lts.add_test_action(ld, test1_action)
ls = LaunchService(argv=argv)
ls.include_launch_description(ld)
return lts.run(ls)


if __name__ == '__main__':
sys.exit(main())
126 changes: 126 additions & 0 deletions nav2_lifecycle_manager/test/test_lifecycle_manager.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,126 @@
// Copyright (c) 2020 Shivang Patel
//
// 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 <gtest/gtest.h>
#include <memory>
#include <chrono>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "nav2_util/node_thread.hpp"
#include "nav2_lifecycle_manager/lifecycle_manager_client.hpp"

using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;

class LifecycleNodeTest : public rclcpp_lifecycle::LifecycleNode
{
public:
LifecycleNodeTest()
: rclcpp_lifecycle::LifecycleNode("lifecycle_node_test") {}

CallbackReturn on_configure(const rclcpp_lifecycle::State & /*state*/) override
{
RCLCPP_INFO(get_logger(), "Lifecycle Test node is Configured!");
return CallbackReturn::SUCCESS;
}

CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) override
{
RCLCPP_INFO(get_logger(), "Lifecycle Test node is Activated!");
return CallbackReturn::SUCCESS;
}

CallbackReturn on_deactivate(const rclcpp_lifecycle::State & /*state*/) override
{
RCLCPP_INFO(get_logger(), "Lifecycle Test node is Deactivated!");
return CallbackReturn::SUCCESS;
}

CallbackReturn on_cleanup(const rclcpp_lifecycle::State & /*state*/) override
{
RCLCPP_INFO(get_logger(), "Lifecycle Test node is Cleanup!");
return CallbackReturn::SUCCESS;
}

CallbackReturn on_shutdown(const rclcpp_lifecycle::State & /*state*/) override
{
RCLCPP_INFO(get_logger(), "Lifecycle Test node is Shutdown!");
return CallbackReturn::SUCCESS;
}

CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/) override
{
RCLCPP_INFO(get_logger(), "Lifecycle Test node is encountered an error!");
return CallbackReturn::SUCCESS;
}
};

class LifecycleClientTestFixture
{
public:
LifecycleClientTestFixture()
{
lf_node_ = std::make_shared<LifecycleNodeTest>();
lf_thread_ = std::make_unique<nav2_util::NodeThread>(lf_node_->get_node_base_interface());
}

private:
std::shared_ptr<LifecycleNodeTest> lf_node_;
std::unique_ptr<nav2_util::NodeThread> lf_thread_;
};

TEST(LifecycleClientTest, BasicTest)
{
LifecycleClientTestFixture fix;
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test");
EXPECT_TRUE(client.startup());
EXPECT_EQ(
nav2_lifecycle_manager::SystemStatus::TIMEOUT,
client.is_active(std::chrono::nanoseconds(1000)));
EXPECT_EQ(
nav2_lifecycle_manager::SystemStatus::ACTIVE,
client.is_active(std::chrono::nanoseconds(1000000000)));
EXPECT_EQ(
nav2_lifecycle_manager::SystemStatus::ACTIVE,
client.is_active());
EXPECT_TRUE(client.pause());
EXPECT_EQ(
nav2_lifecycle_manager::SystemStatus::INACTIVE,
client.is_active(std::chrono::nanoseconds(1000000000)));
EXPECT_TRUE(client.resume());
EXPECT_TRUE(client.reset());
EXPECT_TRUE(client.shutdown());
}

TEST(LifecycleClientTest, WithoutFixture)
{
nav2_lifecycle_manager::LifecycleManagerClient client("lifecycle_manager_test");
EXPECT_EQ(
nav2_lifecycle_manager::SystemStatus::TIMEOUT,
client.is_active(std::chrono::nanoseconds(1000)));
}

int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);

// initialize ROS
rclcpp::init(argc, argv);

bool all_successful = RUN_ALL_TESTS();

// shutdown ROS
rclcpp::shutdown();

return all_successful;
}

0 comments on commit 9e304b1

Please sign in to comment.