Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
is_battery_low_condition.cpp
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 #include <string>
17 
18 #include "nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp"
19 
20 namespace nav2_behavior_tree
21 {
22 
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"),
28  min_battery_(0.0),
29  is_voltage_(false),
30  is_battery_low_(false)
31 {
32  initialize();
33 
34  // Spin multiple times due to rclcpp regression in Jazzy requiring a 'warm up' spin
35  callback_group_executor_.spin_some(std::chrono::nanoseconds(1));
36 }
37 
39 {
40  getInput("min_battery", min_battery_);
41  getInput("is_voltage", is_voltage_);
42 
44 }
45 
47 {
48  std::string battery_topic_new;
49  getInput("battery_topic", battery_topic_new);
50 
51  // Only create a new subscriber if the topic has changed or subscriber is empty
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,
57  false);
58  callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
59 
60  battery_sub_ = node_->create_subscription<sensor_msgs::msg::BatteryState>(
61  battery_topic_,
62  std::bind(&IsBatteryLowCondition::batteryCallback, this, std::placeholders::_1),
64  callback_group_);
65  }
66 }
67 
69 {
70  if (!BT::isStatusActive(status())) {
71  initialize();
72  }
73 
74  callback_group_executor_.spin_some();
75  if (is_battery_low_) {
76  return BT::NodeStatus::SUCCESS;
77  }
78  return BT::NodeStatus::FAILURE;
79 }
80 
81 void IsBatteryLowCondition::batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg)
82 {
83  if (is_voltage_) {
84  is_battery_low_ = msg->voltage <= min_battery_;
85  } else {
86  is_battery_low_ = msg->percentage <= min_battery_;
87  }
88 }
89 
90 } // namespace nav2_behavior_tree
91 
92 #include "behaviortree_cpp/bt_factory.h"
93 BT_REGISTER_NODES(factory)
94 {
95  factory.registerNodeType<nav2_behavior_tree::IsBatteryLowCondition>("IsBatteryLow");
96 }
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.