TEST_F(TestExternallyDefinedServices, extern_defined_initialized) { auto node_handle = rclcpp::node::Node::make_shared("base_node"); // mock for externally defined service rcl_service_t service_handle = rcl_get_zero_initialized_service(); rcl_service_options_t service_options = rcl_service_get_default_options(); const rosidl_service_type_support_t * ts = rosidl_typesupport_cpp::get_service_type_support_handle<rclcpp::srv::Mock>(); rcl_ret_t ret = rcl_service_init( &service_handle, node_handle->get_node_base_interface()->get_rcl_node_handle(), ts, "base_node_service", &service_options); if (ret != RCL_RET_OK) { FAIL(); return; } rclcpp::any_service_callback::AnyServiceCallback<rclcpp::srv::Mock> cb; try { rclcpp::service::Service<rclcpp::srv::Mock>( node_handle->get_node_base_interface()->get_shared_rcl_node_handle(), &service_handle, cb); } catch (const std::runtime_error &) { FAIL(); return; } SUCCEED(); }
TEST_F(TestExternallyDefinedServices, extern_defined_destructor) { auto node_handle = rclcpp::Node::make_shared("base_node"); // mock for externally defined service rcl_service_t service_handle = rcl_get_zero_initialized_service(); rcl_service_options_t service_options = rcl_service_get_default_options(); const rosidl_service_type_support_t * ts = rosidl_typesupport_cpp::get_service_type_support_handle<rclcpp::srv::Mock>(); rcl_ret_t ret = rcl_service_init( &service_handle, node_handle->get_node_base_interface()->get_rcl_node_handle(), ts, "base_node_service", &service_options); if (ret != RCL_RET_OK) { FAIL(); return; } rclcpp::AnyServiceCallback<rclcpp::srv::Mock> cb; { // Call constructor rclcpp::Service<rclcpp::srv::Mock> srv_cpp( node_handle->get_node_base_interface()->get_shared_rcl_node_handle(), &service_handle, cb); // Call destructor } if (!service_handle.impl) { FAIL(); return; } SUCCEED(); }
TEST_F(TestFindWeakNodes, allocator_strategy_with_weak_nodes) { // GIVEN // A vector of weak pointers to nodes auto memory_strategy = std::make_shared< rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<>>(); auto existing_node = rclcpp::Node::make_shared("existing_node"); auto dead_node = rclcpp::Node::make_shared("dead_node"); rclcpp::memory_strategy::MemoryStrategy::WeakNodeList weak_nodes; weak_nodes.push_back(existing_node->get_node_base_interface()); weak_nodes.push_back(dead_node->get_node_base_interface()); // AND // Delete dead_node, creating a dangling pointer in weak_nodes dead_node.reset(); ASSERT_FALSE(weak_nodes.front().expired()); ASSERT_TRUE(weak_nodes.back().expired()); // WHEN bool has_invalid_weak_nodes = memory_strategy->collect_entities(weak_nodes); // THEN // The result of finding dangling node pointers should be true ASSERT_TRUE(has_invalid_weak_nodes); // Prevent memory leak due to the order of destruction memory_strategy->clear_handles(); }
TEST_F(TestFindWeakNodes, allocator_strategy_no_weak_nodes) { // GIVEN // A vector of weak pointers to nodes, all valid auto memory_strategy = std::make_shared< rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<>>(); auto existing_node1 = rclcpp::Node::make_shared("existing_node1"); auto existing_node2 = rclcpp::Node::make_shared("existing_node2"); rclcpp::memory_strategy::MemoryStrategy::WeakNodeList weak_nodes; weak_nodes.push_back(existing_node1->get_node_base_interface()); weak_nodes.push_back(existing_node2->get_node_base_interface()); ASSERT_FALSE(weak_nodes.front().expired()); ASSERT_FALSE(weak_nodes.back().expired()); // WHEN bool has_invalid_weak_nodes = memory_strategy->collect_entities(weak_nodes); // THEN // The result of finding dangling node pointers should be false ASSERT_FALSE(has_invalid_weak_nodes); // Prevent memory leak due to the order of destruction memory_strategy->clear_handles(); }
TEST_F(TestExternallyDefinedServices, extern_defined_uninitialized) { auto node_handle = rclcpp::node::Node::make_shared("base_node"); // mock for externally defined service rcl_service_t service_handle = rcl_get_zero_initialized_service(); rclcpp::any_service_callback::AnyServiceCallback<rclcpp::srv::Mock> cb; // don't initialize the service // expect fail try { rclcpp::service::Service<rclcpp::srv::Mock>( node_handle->get_node_base_interface()->get_shared_rcl_node_handle(), &service_handle, cb); } catch (const std::runtime_error &) { SUCCEED(); return; } FAIL(); }