Skip to content

Commit 91d0a83

Browse files
authored
Add IsBatteryLow condition node (#1974)
* Add IsBatteryLow condition node * Update default battery topic and switch to battery % * Fix test * Switch to sensor_msgs/BatteryState * Add option to use voltage by default or switch to percentage * Add sensor_msgs dependency in package.xml * Make percentage default over voltage * Update parameter list
1 parent a359532 commit 91d0a83

File tree

8 files changed

+330
-3
lines changed

8 files changed

+330
-3
lines changed

‎doc/parameters/param_list.md‎

Lines changed: 23 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -667,6 +667,14 @@ When `recovery_plugins` parameter is not overridden, the following default plugi
667667

668668
## Conditions
669669

670+
### BT Node DistanceTraveled
671+
672+
| Input Port | Default | Description |
673+
| ---------- | ------- | ----------- |
674+
| distance | 1.0 | Distance in meters after which the node should return success |
675+
| global_frame | "map" | Reference frame |
676+
| robot_base_frame | "base_link" | Robot base frame |
677+
670678
### BT Node GoalReached
671679

672680
| Input Port | Default | Description |
@@ -675,7 +683,21 @@ When `recovery_plugins` parameter is not overridden, the following default plugi
675683
| global_frame | "map" | Reference frame |
676684
| robot_base_frame | "base_link" | Robot base frame |
677685

678-
### BT Node TransformAvailable (condition)
686+
### BT Node IsBatteryLow
687+
688+
| Input Port | Default | Description |
689+
| ---------- | ------- | ----------- |
690+
| min_battery | N/A | Minimum battery percentage/voltage |
691+
| battery_topic | "/battery_status" | Battery topic |
692+
| is_voltage | false | If true voltage will be used to check for low battery |
693+
694+
### BT Node TimeExpired
695+
696+
| Input Port | Default | Description |
697+
| ---------- | ------- | ----------- |
698+
| seconds | 1.0 | Number of seconds after which node returns success |
699+
700+
### BT Node TransformAvailable
679701

680702
| Input Port | Default | Description |
681703
| ---------- | ------- | ----------- |

‎nav2_behavior_tree/CMakeLists.txt‎

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,9 +6,9 @@ find_package(nav2_common REQUIRED)
66
find_package(rclcpp REQUIRED)
77
find_package(rclcpp_action REQUIRED)
88
find_package(rclcpp_lifecycle REQUIRED)
9-
find_package(std_msgs REQUIRED)
109
find_package(builtin_interfaces REQUIRED)
1110
find_package(geometry_msgs REQUIRED)
11+
find_package(sensor_msgs REQUIRED)
1212
find_package(nav2_msgs REQUIRED)
1313
find_package(nav_msgs REQUIRED)
1414
find_package(behaviortree_cpp_v3 REQUIRED)
@@ -31,6 +31,7 @@ set(dependencies
3131
rclcpp_action
3232
rclcpp_lifecycle
3333
geometry_msgs
34+
sensor_msgs
3435
nav2_msgs
3536
nav_msgs
3637
behaviortree_cpp_v3
@@ -89,6 +90,9 @@ list(APPEND plugin_libs nav2_distance_traveled_condition_bt_node)
8990
add_library(nav2_initial_pose_received_condition_bt_node SHARED plugins/condition/initial_pose_received_condition.cpp)
9091
list(APPEND plugin_libs nav2_initial_pose_received_condition_bt_node)
9192

93+
add_library(nav2_is_battery_low_condition_bt_node SHARED plugins/condition/is_battery_low_condition.cpp)
94+
list(APPEND plugin_libs nav2_is_battery_low_condition_bt_node)
95+
9296
add_library(nav2_reinitialize_global_localization_service_bt_node SHARED plugins/action/reinitialize_global_localization_service.cpp)
9397
list(APPEND plugin_libs nav2_reinitialize_global_localization_service_bt_node)
9498

‎nav2_behavior_tree/README.md‎

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,7 @@ The nav2_behavior_tree package provides several navigation-specific nodes that a
7272
| IsStuck | Condition | Determines if the robot is not progressing towards the goal. If the robot is stuck and not progressing, the condition returns SUCCESS, otherwise it returns FAILURE. |
7373
| TransformAvailable | Condition | Checks if a TF transform is available. Returns failure if it cannot be found. Once found, it will always return success. Useful for initial condition checks. |
7474
| GoalUpdated | Condition | Checks if the global navigation goal has changed in the blackboard. Returns failure if the goal is the same, if it changes, it returns success. |
75+
| IsBatteryLow | Condition | Checks if battery is low by subscribing to a sensor_msgs/BatteryState topic and checking if battery voltage/percentage is below a specified minimum value. |
7576
| NavigateToPose | Action | Invokes the NavigateToPose ROS2 action server, which is implemented by the bt_navigator module. |
7677
| RateController | Decorator | A node that throttles the tick rate for its child. The tick rate can be supplied to the node as a parameter. The node returns RUNNING when it is not ticking its child. Currently, in the navigation stack, the `RateController` is used to adjust the rate at which the `ComputePathToPose` and `GoalReached` nodes are ticked. |
7778
| DistanceController | Decorator | A node that controls the tick rate for its child based on the distance traveled. The distance to be traveled before replanning can be supplied to the node as a parameter. The node returns RUNNING when it is not ticking its child. Currently, in the navigation stack, the `DistanceController` is used to adjust the rate at which the `ComputePathToPose` and `GoalReached` nodes are ticked. |
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
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+
23+
#include "rclcpp/rclcpp.hpp"
24+
#include "sensor_msgs/msg/battery_state.hpp"
25+
#include "behaviortree_cpp_v3/condition_node.h"
26+
27+
namespace nav2_behavior_tree
28+
{
29+
30+
class IsBatteryLowCondition : public BT::ConditionNode
31+
{
32+
public:
33+
IsBatteryLowCondition(
34+
const std::string & condition_name,
35+
const BT::NodeConfiguration & conf);
36+
37+
IsBatteryLowCondition() = delete;
38+
39+
BT::NodeStatus tick() override;
40+
41+
static BT::PortsList providedPorts()
42+
{
43+
return {
44+
BT::InputPort<double>("min_battery", "Minimum battery percentage/voltage"),
45+
BT::InputPort<std::string>(
46+
"battery_topic", std::string("/battery_status"), "Battery topic"),
47+
BT::InputPort<bool>(
48+
"is_voltage", false, "If true voltage will be used to check for low battery"),
49+
};
50+
}
51+
52+
private:
53+
void batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg);
54+
55+
rclcpp::Node::SharedPtr node_;
56+
rclcpp::Subscription<sensor_msgs::msg::BatteryState>::SharedPtr battery_sub_;
57+
std::string battery_topic_;
58+
double min_battery_;
59+
bool is_voltage_;
60+
bool is_battery_low_;
61+
std::mutex mutex_;
62+
};
63+
64+
} // namespace nav2_behavior_tree
65+
66+
#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_BATTERY_LOW_CONDITION_HPP_

‎nav2_behavior_tree/package.xml‎

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,10 @@
1717
<build_depend>rclcpp</build_depend>
1818
<build_depend>rclcpp_action</build_depend>
1919
<build_depend>rclcpp_lifecycle</build_depend>
20-
<build_depend>std_msgs</build_depend>
2120
<build_depend>behaviortree_cpp_v3</build_depend>
2221
<build_depend>builtin_interfaces</build_depend>
2322
<build_depend>geometry_msgs</build_depend>
23+
<build_depend>sensor_msgs</build_depend>
2424
<build_depend>nav2_msgs</build_depend>
2525
<build_depend>nav_msgs</build_depend>
2626
<build_depend>tf2</build_depend>
@@ -39,6 +39,7 @@
3939
<exec_depend>behaviortree_cpp_v3</exec_depend>
4040
<exec_depend>builtin_interfaces</exec_depend>
4141
<exec_depend>geometry_msgs</exec_depend>
42+
<exec_depend>sensor_msgs</exec_depend>
4243
<exec_depend>nav2_msgs</exec_depend>
4344
<exec_depend>nav_msgs</exec_depend>
4445
<exec_depend>tf2</exec_depend>
Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
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+
getInput("min_battery", min_battery_);
33+
getInput("battery_topic", battery_topic_);
34+
getInput("is_voltage", is_voltage_);
35+
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
36+
battery_sub_ = node_->create_subscription<sensor_msgs::msg::BatteryState>(
37+
battery_topic_,
38+
rclcpp::SystemDefaultsQoS(),
39+
std::bind(&IsBatteryLowCondition::batteryCallback, this, std::placeholders::_1));
40+
}
41+
42+
BT::NodeStatus IsBatteryLowCondition::tick()
43+
{
44+
std::lock_guard<std::mutex> lock(mutex_);
45+
if (is_battery_low_) {
46+
return BT::NodeStatus::SUCCESS;
47+
}
48+
return BT::NodeStatus::FAILURE;
49+
}
50+
51+
void IsBatteryLowCondition::batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg)
52+
{
53+
std::lock_guard<std::mutex> lock(mutex_);
54+
if (is_voltage_) {
55+
is_battery_low_ = msg->voltage <= min_battery_;
56+
} else {
57+
is_battery_low_ = msg->percentage <= min_battery_;
58+
}
59+
}
60+
61+
} // namespace nav2_behavior_tree
62+
63+
#include "behaviortree_cpp_v3/bt_factory.h"
64+
BT_REGISTER_NODES(factory)
65+
{
66+
factory.registerNodeType<nav2_behavior_tree::IsBatteryLowCondition>("IsBatteryLow");
67+
}

‎nav2_behavior_tree/test/plugins/condition/CMakeLists.txt‎

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,3 +25,7 @@ ament_target_dependencies(test_condition_transform_available ${dependencies})
2525
ament_add_gtest(test_condition_is_stuck test_is_stuck.cpp)
2626
target_link_libraries(test_condition_is_stuck nav2_is_stuck_condition_bt_node)
2727
ament_target_dependencies(test_condition_is_stuck ${dependencies})
28+
29+
ament_add_gtest(test_condition_is_battery_low test_is_battery_low.cpp)
30+
target_link_libraries(test_condition_is_battery_low nav2_is_battery_low_condition_bt_node)
31+
ament_target_dependencies(test_condition_is_battery_low ${dependencies})

0 commit comments

Comments
 (0)