Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add IsStoppedBTNode #4764

Open
wants to merge 19 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 9 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions nav2_behavior_tree/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,9 @@ list(APPEND plugin_libs nav2_clear_costmap_service_bt_node)
add_library(nav2_is_stuck_condition_bt_node SHARED plugins/condition/is_stuck_condition.cpp)
list(APPEND plugin_libs nav2_is_stuck_condition_bt_node)

add_library(nav2_is_stopped_condition_bt_node SHARED plugins/condition/is_stopped_condition.cpp)
list(APPEND plugin_libs nav2_is_stopped_condition_bt_node)

add_library(nav2_transform_available_condition_bt_node SHARED plugins/condition/transform_available_condition.cpp)
list(APPEND plugin_libs nav2_transform_available_condition_bt_node)

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,86 @@
// Copyright (c) 2024 Angsa Robotics
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STOPPED_CONDITION_HPP_
#define NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STOPPED_CONDITION_HPP_

#include <string>
#include <atomic>
#include <deque>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "behaviortree_cpp/condition_node.h"
#include "nav_msgs/msg/odometry.hpp"
#include "nav2_util/odometry_utils.hpp"

namespace nav2_behavior_tree
{

/**
* @brief A BT::ConditionNode that tracks robot odometry and returns SUCCESS
* if robot is considered stopped for long enough, RUNNING if stopped but not for long enough and FAILURE otherwise
*/
class IsStoppedCondition : public BT::ConditionNode
{
public:
/**
* @brief A constructor for nav2_behavior_tree::IsStoppedCondition
* @param condition_name Name for the XML tag for this node
* @param conf BT node configuration
*/
IsStoppedCondition(
const std::string & condition_name,
const BT::NodeConfiguration & conf);

IsStoppedCondition() = delete;

/**
* @brief A destructor for nav2_behavior_tree::IsStoppedCondition
*/
~IsStoppedCondition() override;

/**
* @brief The main override required by a BT action
* @return BT::NodeStatus Status of tick execution
*/
BT::NodeStatus tick() override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing node-specific ports
*/
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("velocity_threshold", 0.1,
"Velocity threshold below which robot is considered stopped"),
BT::InputPort<std::chrono::milliseconds>("duration_stopped", 1000,
"Duration (ms) the velocity must remain below the threshold."),
};
}

private:
rclcpp::Node::SharedPtr node_;

double velocity_threshold_;
std::chrono::milliseconds duration_stopped_;
rclcpp::Time stopped_stamp_;

std::shared_ptr<nav2_util::OdomSmoother> odom_smoother_;
};

} // namespace nav2_behavior_tree

#endif // NAV2_BEHAVIOR_TREE__PLUGINS__CONDITION__IS_STOPPED_CONDITION_HPP_
78 changes: 78 additions & 0 deletions nav2_behavior_tree/plugins/condition/is_stopped_condition.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
// Copyright (c) 2024 Angsa Robotics
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <string>
#include <chrono>

#include "nav2_behavior_tree/plugins/condition/is_stopped_condition.hpp"
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved

using namespace std::chrono_literals; // NOLINT

namespace nav2_behavior_tree
{

IsStoppedCondition::IsStoppedCondition(
const std::string & condition_name,
const BT::NodeConfiguration & conf)
: BT::ConditionNode(condition_name, conf),
velocity_threshold_(0.1),
duration_stopped_(1000),
stopped_stamp_(rclcpp::Time(0, 0, RCL_ROS_TIME))
{
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
odom_smoother_ = config().blackboard->get<std::shared_ptr<nav2_util::OdomSmoother>>(
"odom_smoother");
}

IsStoppedCondition::~IsStoppedCondition()
{
RCLCPP_DEBUG(node_->get_logger(), "Shutting down IsStoppedCondition BT node");
}

BT::NodeStatus IsStoppedCondition::tick()
{
auto twist = odom_smoother_->getRawTwistStamped();

// if there is no timestamp, set it to now
if (twist.header.stamp.sec == 0 && twist.header.stamp.nanosec == 0) {
twist.header.stamp = node_->get_clock()->now();
}

if (abs(twist.twist.linear.x) < velocity_threshold_ &&
abs(twist.twist.linear.y) < velocity_threshold_ &&
abs(twist.twist.angular.z) < velocity_threshold_)
{
if (stopped_stamp_ == rclcpp::Time(0, 0, RCL_ROS_TIME)) {
stopped_stamp_ = rclcpp::Time(twist.header.stamp);
}

if (node_->get_clock()->now() - stopped_stamp_ > rclcpp::Duration(duration_stopped_)) {
return BT::NodeStatus::SUCCESS;
} else {
return BT::NodeStatus::RUNNING;
}

} else {
stopped_stamp_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
return BT::NodeStatus::FAILURE;
}
}

} // namespace nav2_behavior_tree

#include "behaviortree_cpp/bt_factory.h"
BT_REGISTER_NODES(factory)
{
factory.registerNodeType<nav2_behavior_tree::IsStoppedCondition>("IsStopped");
}
2 changes: 0 additions & 2 deletions nav2_behavior_tree/plugins/decorator/speed_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,6 @@ SpeedController::SpeedController(
d_rate_ = max_rate_ - min_rate_;
d_speed_ = max_speed_ - min_speed_;

std::string odom_topic;
node_->get_parameter_or("odom_topic", odom_topic, std::string("odom"));
odom_smoother_ = config().blackboard->get<std::shared_ptr<nav2_util::OdomSmoother>>(
"odom_smoother");
}
Expand Down
35 changes: 33 additions & 2 deletions nav2_util/include/nav2_util/odometry_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,13 +68,44 @@ class OdomSmoother
* @brief Get twist msg from smoother
* @return twist Twist msg
*/
inline geometry_msgs::msg::Twist getTwist() {return vel_smooth_.twist;}
inline geometry_msgs::msg::Twist getTwist()
{
std::lock_guard<std::mutex> lock(odom_mutex_);
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
return vel_smooth_.twist;
}

/**
* @brief Get twist stamped msg from smoother
* @return twist TwistStamped msg
*/
inline geometry_msgs::msg::TwistStamped getTwistStamped() {return vel_smooth_;}
inline geometry_msgs::msg::TwistStamped getTwistStamped()
{
std::lock_guard<std::mutex> lock(odom_mutex_);
return vel_smooth_;
}

/**
* @brief Get raw twist msg from smoother (without smoothing)
* @return twist Twist msg
*/
inline geometry_msgs::msg::Twist getRawTwist()
{
std::lock_guard<std::mutex> lock(odom_mutex_);
return odom_history_.back().twist.twist;
}

/**
* @brief Get raw twist stamped msg from smoother (without smoothing)
* @return twist TwistStamped msg
*/
inline geometry_msgs::msg::TwistStamped getRawTwistStamped()
{
std::lock_guard<std::mutex> lock(odom_mutex_);
geometry_msgs::msg::TwistStamped twist_stamped;
twist_stamped.header = odom_history_.back().header;
twist_stamped.twist = odom_history_.back().twist.twist;
return twist_stamped;
}

protected:
/**
Expand Down
Loading