@@ -35,8 +35,6 @@ IsBatteryLowCondition::IsBatteryLowCondition(
3535void IsBatteryLowCondition::initialize ()
3636{
3737 getInput (" min_battery" , min_battery_);
38- std::string battery_topic_new;
39- getInput (" battery_topic" , battery_topic_new);
4038 getInput (" is_voltage" , is_voltage_);
4139
4240 // Only create a new subscriber if the topic has changed or subscriber is empty
@@ -48,19 +46,25 @@ void IsBatteryLowCondition::initialize()
4846
4947void IsBatteryLowCondition::createROSInterfaces ()
5048{
51- node_ = config ().blackboard ->get <rclcpp::Node::SharedPtr>(" node" );
52- callback_group_ = node_->create_callback_group (
53- rclcpp::CallbackGroupType::MutuallyExclusive,
54- false );
55- callback_group_executor_.add_callback_group (callback_group_, node_->get_node_base_interface ());
49+ std::string battery_topic_new;
50+ getInput (" battery_topic" , battery_topic_new);
5651
57- rclcpp::SubscriptionOptions sub_option;
58- sub_option.callback_group = callback_group_;
59- battery_sub_ = node_->create_subscription <sensor_msgs::msg::BatteryState>(
60- battery_topic_,
61- rclcpp::SystemDefaultsQoS (),
62- std::bind (&IsBatteryLowCondition::batteryCallback, this , std::placeholders::_1),
63- sub_option);
52+ if (battery_topic_new != battery_topic_ || !battery_sub_) {
53+ battery_topic_ = battery_topic_new;
54+ node_ = config ().blackboard ->get <rclcpp::Node::SharedPtr>(" node" );
55+ callback_group_ = node_->create_callback_group (
56+ rclcpp::CallbackGroupType::MutuallyExclusive,
57+ false );
58+ callback_group_executor_.add_callback_group (callback_group_, node_->get_node_base_interface ());
59+
60+ rclcpp::SubscriptionOptions sub_option;
61+ sub_option.callback_group = callback_group_;
62+ battery_sub_ = node_->create_subscription <sensor_msgs::msg::BatteryState>(
63+ battery_topic_,
64+ rclcpp::SystemDefaultsQoS (),
65+ std::bind (&IsBatteryLowCondition::batteryCallback, this , std::placeholders::_1),
66+ sub_option);
67+ }
6468}
6569
6670BT::NodeStatus IsBatteryLowCondition::tick ()
0 commit comments