Skip to content
Merged
Show file tree
Hide file tree
Changes from all 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
2 changes: 1 addition & 1 deletion .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
"dockerfile": "../Dockerfile",
"context": "..",
"target": "visualizer",
"cacheFrom": "ghcr.io/ros-planning/navigation2:humble"
"cacheFrom": "ghcr.io/ros-navigation/navigation2:humble"
},
"runArgs": [
// "--cap-add=SYS_PTRACE", // enable debugging, e.g. gdb
Expand Down
2 changes: 1 addition & 1 deletion Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ COPY --from=caddyer /usr/bin/caddy /usr/bin/caddy

# download media files
RUN mkdir -p $ROOT_SRV/media && cd /tmp && \
export ICONS="icons.tar.gz" && wget https://github.com/ros-planning/navigation2/files/11506823/$ICONS && \
export ICONS="icons.tar.gz" && wget https://github.com/ros-navigation/navigation2/files/11506823/$ICONS && \
echo "cae5e2a5230f87b004c8232b579781edb4a72a7431405381403c6f9e9f5f7d41 $ICONS" | sha256sum -c && \
tar xvz -C $ROOT_SRV/media -f $ICONS && rm $ICONS

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__NAVIGATE_THROUGH_POSES_ACTION_HPP_

#include <string>
#include <vector>

#include "geometry_msgs/msg/point.hpp"
#include "geometry_msgs/msg/quaternion.hpp"
Expand Down Expand Up @@ -55,7 +56,8 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
{
return providedBasicPorts(
{
BT::InputPort<geometry_msgs::msg::PoseStamped>("goals", "Destinations to plan through"),
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
"goals", "Destinations to plan through"),
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
});
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,25 @@
using namespace std::chrono; // NOLINT
using namespace std::chrono_literals; // NOLINT

// Shim BT node to access protected resetStatus method
class ShimNode : public nav2_behavior_tree::SingleTrigger
{
public:
ShimNode(
const std::string & name,
const BT::NodeConfiguration & confi)
: SingleTrigger(name, confi)
{}
~ShimNode() {}
void changeStatus() {resetStatus();}
};

class SingleTriggerTestFixture : public nav2_behavior_tree::BehaviorTreeTestFixture
{
public:
void SetUp()
{
bt_node_ = std::make_shared<nav2_behavior_tree::SingleTrigger>(
"single_trigger", *config_);
bt_node_ = std::make_shared<ShimNode>("single_trigger", *config_);
dummy_node_ = std::make_shared<nav2_behavior_tree::DummyNode>();
bt_node_->setChild(dummy_node_.get());
}
Expand All @@ -42,11 +54,11 @@ class SingleTriggerTestFixture : public nav2_behavior_tree::BehaviorTreeTestFixt
}

protected:
static std::shared_ptr<nav2_behavior_tree::SingleTrigger> bt_node_;
static std::shared_ptr<ShimNode> bt_node_;
static std::shared_ptr<nav2_behavior_tree::DummyNode> dummy_node_;
};

std::shared_ptr<nav2_behavior_tree::SingleTrigger>
std::shared_ptr<ShimNode>
SingleTriggerTestFixture::bt_node_ = nullptr;
std::shared_ptr<nav2_behavior_tree::DummyNode>
SingleTriggerTestFixture::dummy_node_ = nullptr;
Expand All @@ -71,6 +83,7 @@ TEST_F(SingleTriggerTestFixture, test_behavior)
// halt BT for a new execution run, should work when dummy node is running
// and once when dummy node returns success and then fail
bt_node_->halt();
bt_node_->changeStatus(); // BTv3.8+ doesn't reset root node automatically
dummy_node_->changeStatus(BT::NodeStatus::RUNNING);
EXPECT_EQ(bt_node_->executeTick(), BT::NodeStatus::RUNNING);
dummy_node_->changeStatus(BT::NodeStatus::SUCCESS);
Expand Down
2 changes: 1 addition & 1 deletion nav2_mppi_controller/test/utils_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -368,7 +368,7 @@ TEST(UtilsTests, SmootherTest)

// Check that path is smoother
float smoothed_val{0}, original_val{0};
for (unsigned int i = 0; i != noisey_sequence.vx.shape(0); i++) {
for (unsigned int i = 1; i != noisey_sequence.vx.shape(0) - 1; i++) {
smoothed_val += fabs(noisey_sequence.vx(i) - 0.2);
smoothed_val += fabs(noisey_sequence.vy(i) - 0.0);
smoothed_val += fabs(noisey_sequence.wz(i) - 0.3);
Expand Down