@@ -34,21 +34,28 @@ IsBatteryLowCondition::IsBatteryLowCondition(
3434void IsBatteryLowCondition::initialize ()
3535{
3636 getInput (" min_battery" , min_battery_);
37- getInput (" battery_topic" , battery_topic_);
37+ std::string battery_topic_new;
38+ getInput (" battery_topic" , battery_topic_new);
3839 getInput (" is_voltage" , is_voltage_);
39- node_ = config ().blackboard ->get <rclcpp::Node::SharedPtr>(" node" );
40- callback_group_ = node_->create_callback_group (
41- rclcpp::CallbackGroupType::MutuallyExclusive,
42- false );
43- callback_group_executor_.add_callback_group (callback_group_, node_->get_node_base_interface ());
4440
45- rclcpp::SubscriptionOptions sub_option;
46- sub_option.callback_group = callback_group_;
47- battery_sub_ = node_->create_subscription <sensor_msgs::msg::BatteryState>(
48- battery_topic_,
49- rclcpp::SystemDefaultsQoS (),
50- std::bind (&IsBatteryLowCondition::batteryCallback, this , std::placeholders::_1),
51- sub_option);
41+ // Only create a new subscriber if the topic has changed or subscriber is empty
42+ if (battery_topic_new != battery_topic_ || !battery_sub_) {
43+ battery_topic_ = battery_topic_new;
44+
45+ node_ = config ().blackboard ->get <rclcpp::Node::SharedPtr>(" node" );
46+ callback_group_ = node_->create_callback_group (
47+ rclcpp::CallbackGroupType::MutuallyExclusive,
48+ false );
49+ callback_group_executor_.add_callback_group (callback_group_, node_->get_node_base_interface ());
50+
51+ rclcpp::SubscriptionOptions sub_option;
52+ sub_option.callback_group = callback_group_;
53+ battery_sub_ = node_->create_subscription <sensor_msgs::msg::BatteryState>(
54+ battery_topic_,
55+ rclcpp::SystemDefaultsQoS (),
56+ std::bind (&IsBatteryLowCondition::batteryCallback, this , std::placeholders::_1),
57+ sub_option);
58+ }
5259}
5360
5461BT::NodeStatus IsBatteryLowCondition::tick ()
0 commit comments