Skip to content
Closed
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
9 changes: 5 additions & 4 deletions nav2_bt_navigator/src/navigators/navigate_through_poses.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <filesystem>
#include <vector>
#include <string>
#include <set>
Expand Down Expand Up @@ -60,13 +61,13 @@ NavigateThroughPosesNavigator::getDefaultBTFilepath(
nav2::LifecycleNode::WeakPtr parent_node)
{
auto node = parent_node.lock();
std::string pkg_share_dir =
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
std::filesystem::path pkg_share_dir;
ament_index_cpp::get_package_share_directory("nav2_bt_navigator", pkg_share_dir);

auto default_bt_xml_filename = node->declare_or_get_parameter(
"default_nav_through_poses_bt_xml",
pkg_share_dir +
"/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
(pkg_share_dir / "behavior_trees" /
"navigate_through_poses_w_replanning_and_recovery.xml").string());

return default_bt_xml_filename;
}
Expand Down
9 changes: 5 additions & 4 deletions nav2_bt_navigator/src/navigators/navigate_to_pose.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <filesystem>
#include <vector>
#include <string>
#include <memory>
Expand Down Expand Up @@ -62,13 +63,13 @@ NavigateToPoseNavigator::getDefaultBTFilepath(
nav2::LifecycleNode::WeakPtr parent_node)
{
auto node = parent_node.lock();
std::string pkg_share_dir =
ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
std::filesystem::path pkg_share_dir;
ament_index_cpp::get_package_share_directory("nav2_bt_navigator", pkg_share_dir);

auto default_bt_xml_filename = node->declare_or_get_parameter(
"default_nav_to_pose_bt_xml",
pkg_share_dir +
"/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");
(pkg_share_dir /
"behavior_trees " / "navigate_to_pose_w_replanning_and_recovery.xml").string());

return default_bt_xml_filename;
}
Expand Down
9 changes: 7 additions & 2 deletions nav2_core/include/nav2_core/behavior_tree_navigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,11 +15,13 @@
#ifndef NAV2_CORE__BEHAVIOR_TREE_NAVIGATOR_HPP_
#define NAV2_CORE__BEHAVIOR_TREE_NAVIGATOR_HPP_

#include <filesystem>
#include <memory>
#include <string>
#include <vector>
#include <mutex>

#include "ament_index_cpp/get_package_share_directory.hpp"
#include "nav2_util/odometry_utils.hpp"
#include "tf2_ros/buffer.hpp"
#include "rclcpp/rclcpp.hpp"
Expand Down Expand Up @@ -201,10 +203,13 @@ class BehaviorTreeNavigator : public NavigatorBase
// get the default behavior tree for this navigator
std::string default_bt_xml_filename = getDefaultBTFilepath(parent_node);

std::filesystem::path file_path;
ament_index_cpp::get_package_share_directory("nav2_bt_navigator", file_path);
file_path /= "behavior_trees";

auto search_directories = node->declare_or_get_parameter(
"bt_search_directories",
std::vector<std::string>{ament_index_cpp::get_package_share_directory(
"nav2_bt_navigator") + "/behavior_trees"}
std::vector<std::string>{file_path.string()}
);

// Create the Behavior Tree Action Server for this navigator
Expand Down
1 change: 0 additions & 1 deletion nav2_docking/opennav_docking/test/test_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include "nav2_util/geometry_utils.hpp"
#include "nav2_ros_common/node_utils.hpp"
#include "tf2_ros/buffer.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"

// Testing the controller at high level; the nav2_graceful_controller
// Where the control law derives has over 98% test coverage
Expand Down
24 changes: 16 additions & 8 deletions nav2_docking/opennav_docking/test/test_dock_database.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include <chrono>
#include <filesystem>
#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"
#include "opennav_docking/dock_database.hpp"
Expand Down Expand Up @@ -100,12 +101,14 @@ TEST(DatabaseTests, getDockInstancesBadConversionFile)
"dockv1.plugin",
rclcpp::ParameterValue("opennav_docking::SimpleChargingDock"));

std::filesystem::path file_path;
ament_index_cpp::get_package_share_directory("opennav_docking", file_path);

// Set a valid path with a malformed file
node->declare_parameter(
"dock_database",
rclcpp::ParameterValue(
ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_dock_bad_conversion_file.yaml"));
(file_path / "dock_files" / "test_dock_bad_conversion_file.yaml").string()));

opennav_docking::DockDatabase db;
db.initialize(node, nullptr);
Expand Down Expand Up @@ -149,8 +152,10 @@ TEST(DatabaseTests, reloadDbService)
node->create_client<nav2_msgs::srv::ReloadDockDatabase>("test/reload_database");

auto request = std::make_shared<nav2_msgs::srv::ReloadDockDatabase::Request>();
request->filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_dock_file.yaml";
std::filesystem::path filepath;
ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "dock_files" / "test_dock_file.yaml";
request->filepath = filepath.string();
EXPECT_TRUE(client->wait_for_service(1s));
auto result = client->async_call(request);
EXPECT_EQ(
Expand All @@ -160,8 +165,9 @@ TEST(DatabaseTests, reloadDbService)

// Try again with a bogus file
auto request2 = std::make_shared<nav2_msgs::srv::ReloadDockDatabase::Request>();
request2->filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/file_does_not_exist.yaml";
ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "file_does_not_exist.yaml";
request2->filepath = filepath.string();
EXPECT_TRUE(client->wait_for_service(1s));
auto result2 = client->async_call(request2);
EXPECT_EQ(
Expand Down Expand Up @@ -190,8 +196,10 @@ TEST(DatabaseTests, reloadDbMutexLocked)
node->create_client<nav2_msgs::srv::ReloadDockDatabase>("test/reload_database");

auto request = std::make_shared<nav2_msgs::srv::ReloadDockDatabase::Request>();
request->filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_dock_file.yaml";
std::filesystem::path filepath;
ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "dock_files" / "test_dock_file.yaml";
request->filepath = filepath.string();
EXPECT_TRUE(client->wait_for_service(1s));
auto result = client->async_call(request);
EXPECT_EQ(
Expand Down
1 change: 0 additions & 1 deletion nav2_docking/opennav_docking/test/test_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "rclcpp/rclcpp.hpp"
#include "nav2_ros_common/simple_action_server.hpp"
#include "opennav_docking/navigator.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"

// Test navigator

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include "sensor_msgs/msg/battery_state.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "opennav_docking/simple_charging_dock.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.hpp"

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@
#include "sensor_msgs/msg/battery_state.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "opennav_docking/simple_non_charging_dock.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2/utils.hpp"

Expand Down
34 changes: 19 additions & 15 deletions nav2_docking/opennav_docking/test/test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <filesystem>
#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"
#include "opennav_docking/utils.hpp"
Expand Down Expand Up @@ -91,9 +92,10 @@ TEST(UtilsTests, parseDockFile)
{
auto node = std::make_shared<nav2::LifecycleNode>("test4");
DockMap db;
std::string filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_dock_file.yaml";
EXPECT_TRUE(utils::parseDockFile(filepath, node, db));
std::filesystem::path filepath;
ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "dock_files" / "test_dock_file.yaml";
EXPECT_TRUE(utils::parseDockFile(filepath.string(), node, db));
EXPECT_EQ(db.size(), 2u);
EXPECT_EQ(db["dock1"].frame, std::string("mapA"));
EXPECT_EQ(db["dock2"].frame, std::string("map"));
Expand All @@ -115,24 +117,26 @@ TEST(UtilsTests, parseDockFile2)
DockMap db;

// Test with a file that has no docks
std::string filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_no_docks_file.yaml";
EXPECT_FALSE(utils::parseDockFile(filepath, node, db));
std::filesystem::path filepath;

ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "dock_files" / "test_no_docks_file.yaml";
EXPECT_FALSE(utils::parseDockFile(filepath.string(), node, db));

// Test with a file that has no type
filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_dock_no_type_file.yaml";
EXPECT_FALSE(utils::parseDockFile(filepath, node, db));
ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "dock_files" / "test_dock_no_type_file.yaml";

EXPECT_FALSE(utils::parseDockFile(filepath.string(), node, db));

// Test with a file that has no pose
filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_dock_no_pose_file.yaml";
EXPECT_FALSE(utils::parseDockFile(filepath, node, db));
ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "dock_files" / "test_dock_no_pose_file.yaml";

// Test with a file that has wring pose array size
filepath = ament_index_cpp::get_package_share_directory("opennav_docking") +
"/dock_files/test_dock_bad_pose_file.yaml";
EXPECT_FALSE(utils::parseDockFile(filepath, node, db));
ament_index_cpp::get_package_share_directory("opennav_docking", filepath);
filepath = filepath / "dock_files" / "test_dock_bad_pose_file.yaml";
EXPECT_FALSE(utils::parseDockFile(filepath.string(), node, db));
}

TEST(UtilsTests, testgetDockPoseStamped)
Expand Down
1 change: 0 additions & 1 deletion nav2_route/src/graph_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#include <memory>

#include "nav2_route/graph_loader.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"

namespace nav2_route
{
Expand Down
1 change: 0 additions & 1 deletion nav2_route/src/graph_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#include <memory>

#include "nav2_route/graph_saver.hpp"
#include "ament_index_cpp/get_package_share_directory.hpp"

namespace nav2_route
{
Expand Down
15 changes: 9 additions & 6 deletions nav2_route/test/test_geojson_graph_file_loader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include <gtest/gtest.h>
#include <filesystem>
#include <fstream>
#include <string>
#include <nlohmann/json.hpp>
Expand Down Expand Up @@ -348,13 +349,14 @@ TEST(GeoJsonGraphFileLoader, simple_graph)

TEST(GeoJsonGraphFileLoader, sample_graph)
{
auto file_path = ament_index_cpp::get_package_share_directory("nav2_route") +
"/graphs/sample_graph.geojson";
std::filesystem::path file_path;
ament_index_cpp::get_package_share_directory("nav2_route", file_path);
file_path = file_path / "graphs" / "sample_graph.geojson";

Graph graph;
GraphToIDMap graph_to_id_map;
GeoJsonGraphFileLoader graph_file_loader;
bool result = graph_file_loader.loadGraphFromFile(graph, graph_to_id_map, file_path);
bool result = graph_file_loader.loadGraphFromFile(graph, graph_to_id_map, file_path.string());
EXPECT_TRUE(result);

Metadata region;
Expand All @@ -379,10 +381,11 @@ TEST(GeoJsonGraphFileLoader, sample_graph)

TEST(GeoJsonGraphFileLoader, invalid_file)
{
auto file_path = ament_index_cpp::get_package_share_directory("nav2_route") +
"/test/test_graphs/invalid.json";
std::filesystem::path file_path;
ament_index_cpp::get_package_share_directory("nav2_route", file_path);
file_path = file_path / "test" / "test_graphs" / "invalid.json";
GeoJsonGraphFileLoader graph_file_loader;
Graph graph;
GraphToIDMap graph_to_id_map;
EXPECT_FALSE(graph_file_loader.loadGraphFromFile(graph, graph_to_id_map, file_path));
EXPECT_FALSE(graph_file_loader.loadGraphFromFile(graph, graph_to_id_map, file_path.string()));
}
12 changes: 7 additions & 5 deletions nav2_route/test/test_geojson_graph_file_saver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include <gtest/gtest.h>
#include <filesystem>
#include <fstream>
#include <string>
#include <nlohmann/json.hpp>
Expand Down Expand Up @@ -319,19 +320,20 @@ TEST(GeoJsonGraphFileSaver, simple_graph)

TEST(GeoJsonGraphFileSaver, sample_graph)
{
auto file_path = ament_index_cpp::get_package_share_directory("nav2_route") +
"/graphs/sample_graph.geojson";
std::filesystem::path file_path;
ament_index_cpp::get_package_share_directory("nav2_route", file_path);
file_path = file_path / "graphs" / "sample_graph.geojson";

Graph graph;
GraphToIDMap graph_to_id_map;
GeoJsonGraphFileLoader graph_file_loader;
graph_file_loader.loadGraphFromFile(graph, graph_to_id_map, file_path);
graph_file_loader.loadGraphFromFile(graph, graph_to_id_map, file_path.string());
GeoJsonGraphFileSaver graph_file_saver;
bool result = graph_file_saver.saveGraphToFile(graph, file_path);
bool result = graph_file_saver.saveGraphToFile(graph, file_path.string());
EXPECT_TRUE(result);
Graph graph2;
GraphToIDMap graph_to_id_map2;
graph_file_loader.loadGraphFromFile(graph2, graph_to_id_map2, file_path);
graph_file_loader.loadGraphFromFile(graph2, graph_to_id_map2, file_path.string());

Metadata region;
region = graph2[0].metadata.getValue("region", region);
Expand Down
Loading
Loading