Skip to content

Commit a7475eb

Browse files
committed
Create subscriber on constructor
1 parent a33e8d2 commit a7475eb

File tree

2 files changed

+23
-13
lines changed

2 files changed

+23
-13
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,11 @@ class IsBatteryLowCondition : public BT::ConditionNode
5656
*/
5757
void initialize();
5858

59+
/**
60+
* @brief Function to create ROS interfaces
61+
*/
62+
void createROSInterfaces();
63+
5964
/**
6065
* @brief Creates list of BT ports
6166
* @return BT::PortsList Containing node-specific ports

nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp

Lines changed: 18 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@ IsBatteryLowCondition::IsBatteryLowCondition(
2929
is_voltage_(false),
3030
is_battery_low_(false)
3131
{
32+
createROSInterfaces();
3233
}
3334

3435
void IsBatteryLowCondition::initialize()
@@ -41,21 +42,25 @@ void IsBatteryLowCondition::initialize()
4142
// Only create a new subscriber if the topic has changed or subscriber is empty
4243
if (battery_topic_new != battery_topic_ || !battery_sub_) {
4344
battery_topic_ = battery_topic_new;
45+
createROSInterfaces();
46+
}
47+
}
4448

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());
49+
void IsBatteryLowCondition::createROSInterfaces()
50+
{
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());
5056

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-
}
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);
5964
}
6065

6166
BT::NodeStatus IsBatteryLowCondition::tick()

0 commit comments

Comments
 (0)