| 
 | 1 | +// Copyright 2024 Open Source Robotics Foundation, Inc.  | 
 | 2 | +//  | 
 | 3 | +// Licensed under the Apache License, Version 2.0 (the "License");  | 
 | 4 | +// you may not use this file except in compliance with the License.  | 
 | 5 | +// You may obtain a copy of the License at  | 
 | 6 | +//  | 
 | 7 | +//     http://www.apache.org/licenses/LICENSE-2.0  | 
 | 8 | +//  | 
 | 9 | +// Unless required by applicable law or agreed to in writing, software  | 
 | 10 | +// distributed under the License is distributed on an "AS IS" BASIS,  | 
 | 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  | 
 | 12 | +// See the License for the specific language governing permissions and  | 
 | 13 | +// limitations under the License.  | 
 | 14 | + | 
 | 15 | +#include <gtest/gtest.h>  | 
 | 16 | +#include <memory>  | 
 | 17 | +#include <string>  | 
 | 18 | + | 
 | 19 | +#include "lifecycle_msgs/msg/state.hpp"  | 
 | 20 | +#include "lifecycle_msgs/msg/transition.hpp"  | 
 | 21 | + | 
 | 22 | +#include "test_msgs/msg/empty.hpp"  | 
 | 23 | + | 
 | 24 | +#include "rclcpp_lifecycle/lifecycle_node.hpp"  | 
 | 25 | +#include "rclcpp_lifecycle/lifecycle_subscription.hpp"  | 
 | 26 | + | 
 | 27 | +using lifecycle_msgs::msg::State;  | 
 | 28 | +using lifecycle_msgs::msg::Transition;  | 
 | 29 | + | 
 | 30 | +class TestDefaultStateMachine : public ::testing::Test  | 
 | 31 | +{  | 
 | 32 | +protected:  | 
 | 33 | +  static void SetUpTestCase()  | 
 | 34 | +  {  | 
 | 35 | +    rclcpp::init(0, nullptr);  | 
 | 36 | +  }  | 
 | 37 | +  static void TearDownTestCase()  | 
 | 38 | +  {  | 
 | 39 | +    rclcpp::shutdown();  | 
 | 40 | +  }  | 
 | 41 | +};  | 
 | 42 | + | 
 | 43 | +/// We want to test everything for both the wall and generic timer.  | 
 | 44 | +enum class TimerType  | 
 | 45 | +{  | 
 | 46 | +  WALL_TIMER,  | 
 | 47 | +  GENERIC_TIMER,  | 
 | 48 | +};  | 
 | 49 | + | 
 | 50 | +class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode  | 
 | 51 | +{  | 
 | 52 | +public:  | 
 | 53 | +  explicit EmptyLifecycleNode(const std::string & node_name, const TimerType & timer_type)  | 
 | 54 | +  : rclcpp_lifecycle::LifecycleNode(node_name)  | 
 | 55 | +  {  | 
 | 56 | +    // For coverage this is being added here  | 
 | 57 | +    switch (timer_type) {  | 
 | 58 | +      case TimerType::WALL_TIMER:  | 
 | 59 | +        {  | 
 | 60 | +          auto timer = create_wall_timer(std::chrono::seconds(1), []() {});  | 
 | 61 | +          add_timer_handle(timer);  | 
 | 62 | +          break;  | 
 | 63 | +        }  | 
 | 64 | +      case TimerType::GENERIC_TIMER:  | 
 | 65 | +        {  | 
 | 66 | +          auto timer = create_timer(std::chrono::seconds(1), []() {});  | 
 | 67 | +          add_timer_handle(timer);  | 
 | 68 | +          break;  | 
 | 69 | +        }  | 
 | 70 | +    }  | 
 | 71 | +  }  | 
 | 72 | + | 
 | 73 | +  void empty_callback(const test_msgs::msg::Empty msg) {}  | 
 | 74 | +};  | 
 | 75 | + | 
 | 76 | +class TestLifecycleSubscription : public ::testing::TestWithParam<TimerType>  | 
 | 77 | +{  | 
 | 78 | +public:  | 
 | 79 | +  void SetUp()  | 
 | 80 | +  {  | 
 | 81 | +    rclcpp::init(0, nullptr);  | 
 | 82 | +  }  | 
 | 83 | + | 
 | 84 | +  void TearDown()  | 
 | 85 | +  {  | 
 | 86 | +    rclcpp::shutdown();  | 
 | 87 | +  }  | 
 | 88 | +};  | 
 | 89 | + | 
 | 90 | +TEST_P(TestLifecycleSubscription, subscribe_managed_by_node) {  | 
 | 91 | +  auto node = std::make_shared<EmptyLifecycleNode>("node", GetParam());  | 
 | 92 | + | 
 | 93 | +  std::shared_ptr<rclcpp_lifecycle::LifecycleSubscription<test_msgs::msg::Empty>> subscription =  | 
 | 94 | +    node->create_subscription<test_msgs::msg::Empty>(std::string("topic"), rclcpp::QoS(10),  | 
 | 95 | +      bind(&EmptyLifecycleNode::empty_callback, node, std::placeholders::_1));  | 
 | 96 | + | 
 | 97 | +  // transition via LifecycleNode  | 
 | 98 | +  auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;  | 
 | 99 | +  auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;  | 
 | 100 | +  auto ret = reset_key;  | 
 | 101 | + | 
 | 102 | +  EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, node->get_current_state().id());  | 
 | 103 | +  node->trigger_transition(  | 
 | 104 | +    rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE), ret);  | 
 | 105 | +  ASSERT_EQ(success, ret);  | 
 | 106 | +  ret = reset_key;  | 
 | 107 | +  node->trigger_transition(  | 
 | 108 | +    rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE), ret);  | 
 | 109 | +  ASSERT_EQ(success, ret);  | 
 | 110 | +  ret = reset_key;  | 
 | 111 | +  EXPECT_TRUE(subscription->is_activated());  | 
 | 112 | +  {  | 
 | 113 | +    std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());  | 
 | 114 | +    EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));  | 
 | 115 | +  }  | 
 | 116 | +  node->trigger_transition(  | 
 | 117 | +    rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE), ret);  | 
 | 118 | +  ASSERT_EQ(success, ret);  | 
 | 119 | +  ret = reset_key;  | 
 | 120 | +  (void)ret;  // Just to make clang happy  | 
 | 121 | +  EXPECT_FALSE(subscription->is_activated());  | 
 | 122 | +  {  | 
 | 123 | +    std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());  | 
 | 124 | +    EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));  | 
 | 125 | +  }  | 
 | 126 | +}  | 
 | 127 | + | 
 | 128 | +TEST_P(TestLifecycleSubscription, subscribe) {  | 
 | 129 | +  auto node = std::make_shared<EmptyLifecycleNode>("node", GetParam());  | 
 | 130 | + | 
 | 131 | +  std::shared_ptr<rclcpp_lifecycle::LifecycleSubscription<test_msgs::msg::Empty>> subscription =  | 
 | 132 | +    node->create_subscription<test_msgs::msg::Empty>(std::string("topic"), rclcpp::QoS(10),  | 
 | 133 | +      bind(&EmptyLifecycleNode::empty_callback, node, std::placeholders::_1));  | 
 | 134 | + | 
 | 135 | +  // transition via LifecycleSubscription  | 
 | 136 | +  subscription->on_deactivate();  | 
 | 137 | +  EXPECT_FALSE(subscription->is_activated());  | 
 | 138 | +  {  | 
 | 139 | +    std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());  | 
 | 140 | +    EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));  | 
 | 141 | +  }  | 
 | 142 | + | 
 | 143 | +  subscription->on_activate();  | 
 | 144 | +  EXPECT_TRUE(subscription->is_activated());  | 
 | 145 | +  {  | 
 | 146 | +    std::shared_ptr<void> msg_ptr(new test_msgs::msg::Empty());  | 
 | 147 | +    EXPECT_NO_THROW(subscription->handle_message(msg_ptr, rclcpp::MessageInfo()));  | 
 | 148 | +  }  | 
 | 149 | +}  | 
 | 150 | + | 
 | 151 | +INSTANTIATE_TEST_SUITE_P(  | 
 | 152 | +  PerTimerType, TestLifecycleSubscription,  | 
 | 153 | +  ::testing::Values(TimerType::WALL_TIMER, TimerType::GENERIC_TIMER),  | 
 | 154 | +  [](const ::testing::TestParamInfo<TimerType> & info) -> std::string {  | 
 | 155 | +    switch (info.param) {  | 
 | 156 | +      case TimerType::WALL_TIMER:  | 
 | 157 | +        return std::string("wall_timer");  | 
 | 158 | +      case TimerType::GENERIC_TIMER:  | 
 | 159 | +        return std::string("generic_timer");  | 
 | 160 | +      default:  | 
 | 161 | +        break;  | 
 | 162 | +    }  | 
 | 163 | +    return std::string("unknown");  | 
 | 164 | +  }  | 
 | 165 | +);  | 
0 commit comments