15 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_CHARGING_CONDITION_HPP_
16 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_CHARGING_CONDITION_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "sensor_msgs/msg/battery_state.hpp"
24 #include "behaviortree_cpp/condition_node.h"
26 namespace nav2_behavior_tree
44 const std::string & condition_name,
45 const BT::NodeConfiguration & conf);
53 BT::NodeStatus
tick()
override;
62 BT::InputPort<std::string>(
63 "battery_topic", std::string(
"/battery_status"),
"Battery topic")
75 void createROSInterfaces();
81 void batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg);
83 rclcpp::CallbackGroup::SharedPtr callback_group_;
84 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
85 rclcpp::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
86 std::string battery_topic_;
87 bool is_battery_charging_;
A BT::ConditionNode that listens to a battery topic and returns SUCCESS when battery is charging and ...
BT::NodeStatus tick() override
The main override required by a BT action.
static BT::PortsList providedPorts()
Creates list of BT ports.