16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_LOW_CONDITION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_LOW_CONDITION_HPP_
23 #include "rclcpp/rclcpp.hpp"
24 #include "sensor_msgs/msg/battery_state.hpp"
25 #include "behaviortree_cpp/condition_node.h"
27 namespace nav2_behavior_tree
43 const std::string & condition_name,
44 const BT::NodeConfiguration & conf);
52 BT::NodeStatus
tick()
override;
66 BT::InputPort<double>(
"min_battery",
"Minimum battery percentage/voltage"),
67 BT::InputPort<std::string>(
68 "battery_topic", std::string(
"/battery_status"),
"Battery topic"),
70 "is_voltage",
false,
"If true voltage will be used to check for low battery"),
79 void batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg);
81 rclcpp::Node::SharedPtr node_;
82 rclcpp::CallbackGroup::SharedPtr callback_group_;
83 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
84 rclcpp::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
85 std::string battery_topic_;
A BT::ConditionNode that listens to a battery topic and returns SUCCESS when battery is low and FAILU...
static BT::PortsList providedPorts()
Creates list of BT ports.
BT::NodeStatus tick() override
The main override required by a BT action.
void initialize()
Function to read parameters and initialize class variables.