Skip to content

Commit

Permalink
service becomes unresponsive after being destroyed and created again.
Browse files Browse the repository at this point in the history
  ros2/rclcpp#1175

Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Jun 24, 2020
1 parent 450b811 commit 3248760
Show file tree
Hide file tree
Showing 2 changed files with 81 additions and 7 deletions.
15 changes: 8 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,11 +52,12 @@ function(custom_executable target)
endfunction()

# Create an executable
custom_executable(rclcpp_1121)
custom_executable(rclcpp_1148)
custom_executable(ros2_946_pub)
custom_executable(ros2_946_sub)
custom_executable(ros2_644)
#custom_executable(rclcpp_1121)
#custom_executable(rclcpp_1148)
custom_executable(rclcpp_1175)
#custom_executable(ros2_946_pub)
#custom_executable(ros2_946_sub)
#custom_executable(ros2_644)

if ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang" AND
"${CMAKE_CXX_COMPILER_VERSION}" VERSION_LESS 6.0)
Expand All @@ -69,8 +70,8 @@ elseif ("${CMAKE_CXX_COMPILER_ID}" STREQUAL "GNU" AND
message(ERROR "GCC 7 or above required for TSan to work correctly in Debug builds. TSan hasn't been enabled.")
else ()
# Enable TSan
target_compile_options(rclcpp_1121 PRIVATE "-fsanitize=thread")
target_link_options(rclcpp_1121 PRIVATE "-fsanitize=thread")
#target_compile_options(rclcpp_1121 PRIVATE "-fsanitize=thread")
#target_link_options(rclcpp_1121 PRIVATE "-fsanitize=thread")
endif ()

ament_package()
73 changes: 73 additions & 0 deletions src/rclcpp_1175.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
#include <cstdlib>
#include <functional>
#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/set_bool.hpp>
#include <std_srvs/srv/trigger.hpp>

using namespace std::placeholders;
using namespace std::chrono_literals;

using namespace std_srvs::srv;

rclcpp::Node::SharedPtr g_node = nullptr;
rclcpp::Service<Trigger>::SharedPtr g_dynsrv = nullptr;

void handle_dynamic_service(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<Trigger::Request> request,
const std::shared_ptr<Trigger::Response> response)
{
(void) request_header;
(void) request;
RCLCPP_INFO(g_node->get_logger(), "trigger called!");
response->success = true;
}

void handle_enable_service(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<SetBool::Request> request,
const std::shared_ptr<SetBool::Response> response)
{
(void) request_header;
if(request->data)
{
if(g_dynsrv)
{
RCLCPP_INFO(g_node->get_logger(), "already enabled");
response->success = false;
response->message = "already enabled";
}
else
{
RCLCPP_INFO(g_node->get_logger(), "enabling dynamic service");
g_dynsrv = g_node->create_service<Trigger>("dynamic_service", handle_dynamic_service);
response->success = true;
}
}
else
{
if(g_dynsrv)
{
RCLCPP_INFO(g_node->get_logger(), "disabling dynamic service");
g_dynsrv = nullptr;
response->success = true;
}
else
{
RCLCPP_INFO(g_node->get_logger(), "already disabled");
response->success = false;
response->message = "already disabled";
}
}
}

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
g_node = rclcpp::Node::make_shared("test_dynamic_service");
auto enable_server = g_node->create_service<SetBool>("enable", handle_enable_service);
rclcpp::spin(g_node);
rclcpp::shutdown();
g_node = nullptr;
return 0;
}

0 comments on commit 3248760

Please sign in to comment.