Skip to content

Commit

Permalink
Add tests
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
  • Loading branch information
ivanpauno committed Jan 26, 2022
1 parent ee9b93c commit ab63ae6
Show file tree
Hide file tree
Showing 4 changed files with 204 additions and 0 deletions.
12 changes: 12 additions & 0 deletions ros_ign_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -190,10 +190,18 @@ if(BUILD_TESTING)
add_executable(test_ign_subscriber test/subscribers/ign_subscriber.cpp)
target_link_libraries(test_ign_subscriber test_utils)

add_executable(test_ign_server test/serverclient/ign_server.cpp)
target_link_libraries(test_ign_server test_utils)

add_executable(test_ros_client test/serverclient/ros_client.cpp)
target_link_libraries(test_ros_client test_utils)

install(TARGETS
test_ros_client
test_ros_publisher
test_ros_subscriber
test_ign_publisher
test_ign_server
test_ign_subscriber
DESTINATION lib/${PROJECT_NAME}
)
Expand All @@ -205,6 +213,10 @@ if(BUILD_TESTING)
add_launch_test(test/launch/test_ign_subscriber.launch.py
TIMEOUT 200
)

add_launch_test(test/launch/test_ign_server.launch.py
TIMEOUT 200
)
endif()

ament_export_dependencies(
Expand Down
69 changes: 69 additions & 0 deletions ros_ign_bridge/test/launch/test_ign_server.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
# Copyright 2022 Open Source Robotics Foundation, Inc.
#
# 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 unittest

from launch import LaunchDescription

from launch_ros.actions import Node

import launch_testing


def generate_test_description():

publisher = Node(
package='ros_ign_bridge',
executable='test_ign_server',
output='screen'
)
process_under_test = Node(
package='ros_ign_bridge',
executable='test_ros_client',
output='screen'
)

# Bridge
bridge = Node(
package='ros_ign_bridge',
executable='parameter_bridge',
arguments=[
'/ign_ros/test/serviceclient/service@ros_ign_interfaces/srv/ControlWorld',
],
output='screen'
)
return LaunchDescription([
bridge,
publisher,
process_under_test,
launch_testing.util.KeepAliveProc(),
launch_testing.actions.ReadyToTest(),
]), locals()


class ROSSubscriberTest(unittest.TestCase):

def test_termination(self, process_under_test, proc_info):
proc_info.assertWaitForShutdown(process=process_under_test, timeout=200)


@launch_testing.post_shutdown_test()
class ROSSubscriberTestAfterShutdown(unittest.TestCase):

def test_exit_code(self, process_under_test, proc_info):
launch_testing.asserts.assertExitCodes(
proc_info,
[launch_testing.asserts.EXIT_OK],
process_under_test
)
75 changes: 75 additions & 0 deletions ros_ign_bridge/test/serverclient/ign_server.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
// Copyright 2022 Open Source Robotics Foundation, Inc.
//
// 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 <ignition/msgs/boolean.pb.h>
#include <ignition/msgs/world_control.pb.h>

#include <ignition/transport.hh>

#include <atomic>
#include <chrono>
#include <csignal>
#include <iostream>
#include <string>
#include <thread>

#include "utils/test_utils.hpp"
#include "utils/ign_test_msg.hpp"

/// \brief Flag used to break the publisher loop and terminate the program.
static std::atomic_flag g_terminateSrv(false);

//////////////////////////////////////////////////
/// \brief Function callback executed when a SIGINT or SIGTERM signals are
/// captured. This is used to break the infinite loop that handles requests
/// and exit the program smoothly.
void signal_handler(int _signal)
{
if (_signal == SIGINT || _signal == SIGTERM) {
g_terminateSrv.clear();
}
}

//////////////////////////////////////////////////
bool control_world(
const ignition::msgs::WorldControl &,
ignition::msgs::Boolean &_res)
{
_res.set_data(true);
return true;
}

//////////////////////////////////////////////////
int main(int /*argc*/, char **/*argv*/)
{
g_terminateSrv.test_and_set();
// Install a signal handler for SIGINT and SIGTERM.
std::signal(SIGINT, signal_handler);
std::signal(SIGTERM, signal_handler);

// Create a transport node and advertise a topic.
ignition::transport::Node node;

// ignition::msgs::Color.
node.Advertise("/ign_ros/test/serviceclient/service",
&control_world);

// Requests are handled in another thread.
// Wait until a signal is sent.
while (g_terminateSrv.test_and_set()) {
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}

return 0;
}
48 changes: 48 additions & 0 deletions ros_ign_bridge/test/serverclient/ros_client.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// Copyright 2022 Open Source Robotics Foundation, Inc.
//
// 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 <thread>

#include "rclcpp/rclcpp.hpp"

#include "ros_ign_interfaces/srv/control_world.hpp"

using namespace std::chrono_literals;

/////////////////////////////////////////////////
TEST(ROSClientTest, WorldControl)
{
rclcpp::init(0, NULL);
auto node = std::make_shared<rclcpp::Node>("test_ros_client_to_ign_service");
auto client = node->create_client<ros_ign_interfaces::srv::ControlWorld>("/ign_ros/test/serviceclient/service");
std::this_thread::sleep_for(1s);
client->wait_for_service();
auto msg = std::make_shared<ros_ign_interfaces::srv::ControlWorld::Request>();
auto future = client->async_send_request(msg);
rclcpp::executors::SingleThreadedExecutor ex;
ex.add_node(node);
ex.spin_until_future_complete(future);
auto res = future.get();
ASSERT_TRUE(res->success);
}

/////////////////////////////////////////////////
int main(int argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}

0 comments on commit ab63ae6

Please sign in to comment.