Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
is_battery_low_condition.hpp
1 // Copyright (c) 2020 Sarthak Mittal
2 // Copyright (c) 2019 Intel Corporation
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_LOW_CONDITION_HPP_
17 #define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_LOW_CONDITION_HPP_
18 
19 #include <string>
20 #include <memory>
21 #include <mutex>
22 #include <chrono>
23 
24 #include "nav2_ros_common/lifecycle_node.hpp"
25 #include "sensor_msgs/msg/battery_state.hpp"
26 #include "behaviortree_cpp/condition_node.h"
27 
28 namespace nav2_behavior_tree
29 {
30 
37 class IsBatteryLowCondition : public BT::ConditionNode
38 {
39 public:
46  const std::string & condition_name,
47  const BT::NodeConfiguration & conf);
48 
49  IsBatteryLowCondition() = delete;
50 
55  BT::NodeStatus tick() override;
56 
60  void initialize();
61 
65  void createROSInterfaces();
66 
71  static BT::PortsList providedPorts()
72  {
73  return {
74  BT::InputPort<double>("min_battery", "Minimum battery percentage/voltage"),
75  BT::InputPort<std::string>(
76  "battery_topic", std::string("/battery_status"), "Battery topic"),
77  BT::InputPort<bool>(
78  "is_voltage", false, "If true voltage will be used to check for low battery"),
79  };
80  }
81 
82 private:
87  void batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg);
88 
89  nav2::LifecycleNode::SharedPtr node_;
90  rclcpp::CallbackGroup::SharedPtr callback_group_;
91  rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
92  nav2::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
93  std::string battery_topic_;
94  double min_battery_;
95  bool is_voltage_;
96  bool is_battery_low_;
97  std::chrono::milliseconds bt_loop_duration_;
98 };
99 
100 } // namespace nav2_behavior_tree
101 
102 #endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_LOW_CONDITION_HPP_
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.
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.