Skip to content

Commit d50cdf9

Browse files
[tests/test_sot_loader] Makes the test of sending a script working.
The catch is to have the same node, with reentrant type for the server and the client when both are loaded in the same process.
1 parent 8e76a12 commit d50cdf9

File tree

1 file changed

+21
-36
lines changed

1 file changed

+21
-36
lines changed

tests/test_sot_loader.cpp

Lines changed: 21 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,8 @@
33
#include <gmock/gmock.h>
44
#pragma clang diagnostic pop
55

6+
#include <chrono>
7+
68
using namespace std::chrono_literals;
79

810
#include <rclcpp/rclcpp.hpp>
@@ -27,15 +29,17 @@ class MockSotLoaderTest : public ::testing::Test {
2729
subscription_;
2830
bool service_done_;
2931
std::string node_name_;
30-
std::string response_dg_python_result_;
3132

32-
MockSotLoader() : node_name_("unittest_sot_loader") {}
33+
rclcpp::CallbackGroup::SharedPtr reentrant_cb_group_;
3334

34-
~MockSotLoader() {
35-
service_done_ = false;
36-
response_dg_python_result_ = "";
35+
MockSotLoader() : node_name_("unittest_sot_loader") {
36+
reentrant_cb_group_ =
37+
dynamic_graph_bridge::get_ros_node(node_name_)
38+
->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
3739
}
3840

41+
~MockSotLoader() { service_done_ = false; }
42+
3943
void topic_callback(
4044
const dynamic_graph_bridge_msgs::msg::Vector::SharedPtr msg) const {
4145
bool ok = true;
@@ -48,45 +52,27 @@ class MockSotLoaderTest : public ::testing::Test {
4852
// This method is to listen to publication from the control signal (dg
4953
// world) to the control_ros topic (ros world).
5054
void subscribe_to_a_topic() {
55+
rclcpp::SubscriptionOptions subscription_options;
56+
subscription_options.callback_group = reentrant_cb_group_;
5157
subscription_ =
5258
dynamic_graph_bridge::get_ros_node(node_name_)
5359
->create_subscription<dynamic_graph_bridge_msgs::msg::Vector>(
5460
"control_ros", 1,
5561
std::bind(&MockSotLoader::topic_callback, this,
56-
std::placeholders::_1));
57-
}
58-
59-
// This method is to receive the result of client request to run_python_file
60-
//
61-
void response_dg_python(
62-
const rclcpp::Client<dynamic_graph_bridge_msgs::srv::RunPythonFile>::
63-
SharedFuture future) {
64-
RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
65-
"response_dg_python:");
66-
auto status = future.wait_for(500ms);
67-
if (status == std::future_status::ready) {
68-
// uncomment below line if using Empty() message
69-
// RCLCPP_INFO(this->get_logger(), "Result: success");
70-
// comment below line if using Empty() message
71-
RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
72-
"response_dg_python - Result: %s",
73-
future.get()->result.c_str());
74-
service_done_ = true;
75-
response_dg_python_result_ = future.get()->result;
76-
} else {
77-
RCLCPP_INFO(rclcpp::get_logger("dynmic_graph_bridge"),
78-
"response_dg_python - Service In-Progress...");
79-
}
62+
std::placeholders::_1),
63+
subscription_options);
8064
}
8165

8266
void start_run_python_script_ros_service(const std::string& file_name) {
8367
// Service name.
8468
std::string service_name = "/dynamic_graph_bridge/run_python_file";
8569
// Create a client from a temporary node.
70+
rclcpp::CallbackGroup::SharedPtr local_cb_group =
71+
dynamic_graph_bridge::get_callback_group("python_interpreter");
8672
auto client =
87-
dynamic_graph_bridge::get_ros_node(node_name_)
73+
dynamic_graph_bridge::get_ros_node("python_interpreter")
8874
->create_client<dynamic_graph_bridge_msgs::srv::RunPythonFile>(
89-
service_name);
75+
service_name, rclcpp::ServicesQoS(), local_cb_group);
9076
ASSERT_TRUE(client->wait_for_service(1s));
9177

9278
// Fill the command message.
@@ -95,13 +81,13 @@ class MockSotLoaderTest : public ::testing::Test {
9581
dynamic_graph_bridge_msgs::srv::RunPythonFile::Request>();
9682
request->input = file_name;
9783
// Call the service.
98-
auto response = client->async_send_request(
99-
request, std::bind(&MockSotLoader::response_dg_python, this,
100-
std::placeholders::_1));
84+
auto response = client->async_send_request(request);
10185
RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
10286
"Send request to service %s - Waiting", service_name.c_str());
10387
response.wait();
104-
RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"), "Get the answer");
88+
RCLCPP_INFO(rclcpp::get_logger("dynamic_graph_bridge"),
89+
"start_run_python_script_ros_service - Result: %s",
90+
response.get()->result.c_str());
10591
}
10692

10793
void display_services(std::map<std::string, std::vector<std::string>>&
@@ -178,7 +164,6 @@ class MockSotLoaderTest : public ::testing::Test {
178164

179165
// Start the control loop thread.
180166
startControlLoop();
181-
182167
// Start the thread generating events.
183168
std::thread local_events(&MockSotLoader::generateEvents, this);
184169

0 commit comments

Comments
 (0)