Skip to content

Commit

Permalink
Merge branch 'ros-navigation:main' into eigen_mppi
Browse files Browse the repository at this point in the history
  • Loading branch information
Ayush1285 authored Dec 5, 2024
2 parents 00f77e1 + add09f6 commit 61652cd
Show file tree
Hide file tree
Showing 76 changed files with 755 additions and 1,725 deletions.
6 changes: 3 additions & 3 deletions .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ _commands:
- restore_cache:
name: Restore Cache << parameters.key >>
keys:
- "<< parameters.key >>-v28\
- "<< parameters.key >>-v31\
-{{ arch }}\
-{{ .Branch }}\
-{{ .Environment.CIRCLE_PR_NUMBER }}\
-{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}"
- "<< parameters.key >>-v28\
- "<< parameters.key >>-v31\
-{{ arch }}\
-main\
-<no value>\
Expand All @@ -58,7 +58,7 @@ _commands:
steps:
- save_cache:
name: Save Cache << parameters.key >>
key: "<< parameters.key >>-v28\
key: "<< parameters.key >>-v31\
-{{ arch }}\
-{{ .Branch }}\
-{{ .Environment.CIRCLE_PR_NUMBER }}\
Expand Down
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,90 @@
// 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"
#include "nav2_behavior_tree/bt_utils.hpp"


using namespace std::chrono_literals; // NOLINT

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.01,
"Velocity threshold below which robot is considered stopped"),
BT::InputPort<std::chrono::milliseconds>("duration_stopped", 1000ms,
"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_
82 changes: 82 additions & 0 deletions nav2_behavior_tree/include/nav2_behavior_tree/utils/loop_rate.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
// 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__UTILS__LOOP_RATE_HPP_
#define NAV2_BEHAVIOR_TREE__UTILS__LOOP_RATE_HPP_

#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "behaviortree_cpp/bt_factory.h"
#include "behaviortree_cpp/behavior_tree.h"

namespace nav2_behavior_tree
{

class LoopRate
{
public:
LoopRate(const rclcpp::Duration & period, BT::Tree * tree)
: clock_(std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME)), period_(period),
last_interval_(clock_->now()), tree_(tree)
{}

// Similar to rclcpp::WallRate::sleep() but using tree_->sleep()
bool sleep()
{
// Time coming into sleep
auto now = clock_->now();
// Time of next interval
auto next_interval = last_interval_ + period_;
// Detect backwards time flow
if (now < last_interval_) {
// Best thing to do is to set the next_interval to now + period
next_interval = now + period_;
}
// Update the interval
last_interval_ += period_;
// If the time_to_sleep is negative or zero, don't sleep
if (next_interval <= now) {
// If an entire cycle was missed then reset next interval.
// This might happen if the loop took more than a cycle.
// Or if time jumps forward.
if (now > next_interval + period_) {
last_interval_ = now + period_;
}
// Either way do not sleep and return false
return false;
}
// Calculate the time to sleep
auto time_to_sleep = next_interval - now;
std::chrono::nanoseconds time_to_sleep_ns(time_to_sleep.nanoseconds());
// Sleep (can get interrupted by emitWakeUpSignal())
tree_->sleep(time_to_sleep_ns);
return true;
}

std::chrono::nanoseconds period() const
{
return std::chrono::nanoseconds(period_.nanoseconds());
}

private:
rclcpp::Clock::SharedPtr clock_;
rclcpp::Duration period_;
rclcpp::Time last_interval_;
BT::Tree * tree_;
};

} // namespace nav2_behavior_tree

#endif // NAV2_BEHAVIOR_TREE__UTILS__LOOP_RATE_HPP_
5 changes: 5 additions & 0 deletions nav2_behavior_tree/nav2_tree_nodes.xml
Original file line number Diff line number Diff line change
Expand Up @@ -227,6 +227,11 @@

<Condition ID="IsStuck"/>

<Condition ID="IsStopped">
<input_port name="velocity_threshold">Velocity threshold below which robot is considered stopped</input_port>
<input_port name="duration_stopped">Duration (ms) the velocity must remain below the threshold</input_port>
</Condition>

<Condition ID="TransformAvailable">
<input_port name="child">Child frame for transform</input_port>
<input_port name="parent">Parent frame for transform</input_port>
Expand Down
80 changes: 80 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,80 @@
// 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"

namespace nav2_behavior_tree
{

IsStoppedCondition::IsStoppedCondition(
const std::string & condition_name,
const BT::NodeConfiguration & conf)
: BT::ConditionNode(condition_name, conf),
velocity_threshold_(0.01),
duration_stopped_(1000ms),
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()
{
getInput("velocity_threshold", velocity_threshold_);
getInput("duration_stopped", duration_stopped_);

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_)) {
stopped_stamp_ = rclcpp::Time(0, 0, RCL_ROS_TIME);
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");
}
Loading

0 comments on commit 61652cd

Please sign in to comment.