18 #include "nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp"
20 namespace nav2_behavior_tree
23 IsBatteryLowCondition::IsBatteryLowCondition(
24 const std::string & condition_name,
25 const BT::NodeConfiguration & conf)
26 : BT::ConditionNode(condition_name, conf),
27 battery_topic_(
"/battery_status"),
30 is_battery_low_(false)
35 callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
40 getInput(
"min_battery", min_battery_);
41 getInput(
"is_voltage", is_voltage_);
48 std::string battery_topic_new;
49 getInput(
"battery_topic", battery_topic_new);
52 if (battery_topic_new != battery_topic_ || !battery_sub_) {
53 battery_topic_ = battery_topic_new;
54 node_ = config().blackboard->get<nav2::LifecycleNode::SharedPtr>(
"node");
55 callback_group_ = node_->create_callback_group(
56 rclcpp::CallbackGroupType::MutuallyExclusive,
58 callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
60 battery_sub_ = node_->create_subscription<sensor_msgs::msg::BatteryState>(
62 std::bind(&IsBatteryLowCondition::batteryCallback,
this, std::placeholders::_1),
70 if (!BT::isStatusActive(status())) {
74 callback_group_executor_.spin_some();
75 if (is_battery_low_) {
76 return BT::NodeStatus::SUCCESS;
78 return BT::NodeStatus::FAILURE;
81 void IsBatteryLowCondition::batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg)
84 is_battery_low_ = msg->voltage <= min_battery_;
86 is_battery_low_ = msg->percentage <= min_battery_;
92 #include "behaviortree_cpp/bt_factory.h"
93 BT_REGISTER_NODES(factory)
A QoS profile for standard reliable topics with a history of 10 messages.
A BT::ConditionNode that listens to a battery topic and returns SUCCESS when battery is low and FAILU...
void createROSInterfaces()
Function to create ROS interfaces.
BT::NodeStatus tick() override
The main override required by a BT action.
void initialize()
Function to read parameters and initialize class variables.