From 465e4e1d70cf0bf4869c6297d7ad15ae7017bef5 Mon Sep 17 00:00:00 2001 From: stevemacenski <stevenmacenski@gmail.com> Date: Tue, 10 Sep 2019 14:33:26 -0700 Subject: [PATCH] removing nav2_msgs/path in favor of nav_msgs/Path which inherently contains more information --- .../nav2_behavior_tree/compute_path_to_pose_action.hpp | 3 ++- .../include/nav2_behavior_tree/follow_path_action.hpp | 4 ++-- .../include/nav2_bt_navigator/bt_navigator.hpp | 4 ++-- nav2_bt_navigator/src/bt_navigator.cpp | 4 ++-- nav2_core/include/nav2_core/global_planner.hpp | 9 ++------- nav2_core/include/nav2_core/recovery.hpp | 5 ----- .../include/dwb_controller/dwb_controller.hpp | 2 +- .../dwb_controller/src/dwb_controller.cpp | 2 +- .../nav_2d_utils/include/nav_2d_utils/conversions.hpp | 3 +-- nav2_dwb_controller/nav_2d_utils/src/conversions.cpp | 4 ++-- nav2_msgs/CMakeLists.txt | 4 ++-- nav2_msgs/action/ComputePathToPose.action | 2 +- nav2_msgs/action/FollowPath.action | 2 +- nav2_msgs/msg/Path.msg | 4 ---- nav2_msgs/package.xml | 1 + nav2_navfn_planner/CMakeLists.txt | 1 + nav2_system_tests/src/planning/planner_tester.hpp | 4 ++-- .../src/planning/test_planner_costmaps_node.cpp | 2 +- .../src/planning/test_planner_random_node.cpp | 2 +- 19 files changed, 25 insertions(+), 37 deletions(-) delete mode 100644 nav2_msgs/msg/Path.msg diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp index c4c29ed0..32483fd4 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/compute_path_to_pose_action.hpp @@ -19,6 +19,7 @@ #include <string> #include "nav2_msgs/action/compute_path_to_pose.hpp" +#include "nav_msgs/msg/path.h" #include "nav2_behavior_tree/bt_action_node.hpp" namespace nav2_behavior_tree @@ -39,7 +40,7 @@ public: void on_success() override { - *(blackboard()->get<nav2_msgs::msg::Path::SharedPtr>("path")) = result_.result->path; + *(blackboard()->get<nav_msgs::msg::Path::SharedPtr>("path")) = result_.result->path; if (first_time_) { first_time_ = false; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/follow_path_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/follow_path_action.hpp index 923eddc8..c0e35a55 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/follow_path_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/follow_path_action.hpp @@ -39,7 +39,7 @@ public: void on_tick() override { - goal_.path = *(blackboard()->get<nav2_msgs::msg::Path::SharedPtr>("path")); + goal_.path = *(blackboard()->get<nav_msgs::msg::Path::SharedPtr>("path")); } void on_loop_timeout() override @@ -51,7 +51,7 @@ public: // Grab the new goal and set the flag so that we send the new goal to // the action server on the next loop iteration - goal_.path = *(blackboard()->get<nav2_msgs::msg::Path::SharedPtr>("path")); + goal_.path = *(blackboard()->get<nav_msgs::msg::Path::SharedPtr>("path")); goal_updated_ = true; } } diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp index ee1abeff..a468f937 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp @@ -23,7 +23,7 @@ #include "nav2_behavior_tree/behavior_tree_engine.hpp" #include "nav2_util/lifecycle_node.hpp" #include "nav2_msgs/action/navigate_to_pose.hpp" -#include "nav2_msgs/msg/path.hpp" +#include "nav_msgs/msg/path.hpp" #include "nav2_util/simple_action_server.hpp" #include "rclcpp_action/rclcpp_action.hpp" @@ -67,7 +67,7 @@ protected: std::shared_ptr<geometry_msgs::msg::PoseStamped> goal_; // The path (on the blackboard) to be returned from ComputePath and sent to the FollowPath task - std::shared_ptr<nav2_msgs::msg::Path> path_; + std::shared_ptr<nav_msgs::msg::Path> path_; // The XML string that defines the Behavior Tree to create std::string xml_string_; diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 7601a88b..e9751ee1 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -69,14 +69,14 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/) // Create the path that will be returned from ComputePath and sent to FollowPath goal_ = std::make_shared<geometry_msgs::msg::PoseStamped>(); - path_ = std::make_shared<nav2_msgs::msg::Path>(); + path_ = std::make_shared<nav_msgs::msg::Path>(); // Create the blackboard that will be shared by all of the nodes in the tree blackboard_ = BT::Blackboard::create<BT::BlackboardLocal>(); // Put items on the blackboard blackboard_->set<geometry_msgs::msg::PoseStamped::SharedPtr>("goal", goal_); // NOLINT - blackboard_->set<nav2_msgs::msg::Path::SharedPtr>("path", path_); // NOLINT + blackboard_->set<nav_msgs::msg::Path::SharedPtr>("path", path_); // NOLINT blackboard_->set<rclcpp::Node::SharedPtr>("node", client_node_); // NOLINT blackboard_->set<std::chrono::milliseconds>("node_loop_timeout", std::chrono::milliseconds(10)); // NOLINT blackboard_->set<bool>("path_updated", false); // NOLINT diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp index 810433ef..92d28ea4 100644 --- a/nav2_core/include/nav2_core/global_planner.hpp +++ b/nav2_core/include/nav2_core/global_planner.hpp @@ -19,7 +19,7 @@ #include "rclcpp/rclcpp.h" #include "nav2_costmap_2d/nav2_costmap_2d.hpp" #include "tf2_ros/Buffer.h" -#include "nav2_msgs/msg/path.h" +#include "nav_msgs/msg/path.h" #include "geometry_msgs/msg/pose_stamped.h" namespace nav2_core @@ -62,18 +62,13 @@ public: */ virtual void deactivate() = 0; - /** - * @brief Method to shutdown planner and any threads involved in execution. - */ - virtual void shutdown() = 0; - /** * @brief Method create the plan from a starting and ending goal. * @param start The starting pose of the robot * @param goal The goal pose of the robot * @return The sequence of poses to get from start to goal, if any */ - virtual nav2_msgs::Path createPlan( + virtual nav_msgs::msg::Path createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) = 0; }; diff --git a/nav2_core/include/nav2_core/recovery.hpp b/nav2_core/include/nav2_core/recovery.hpp index e097a026..1945b87d 100644 --- a/nav2_core/include/nav2_core/recovery.hpp +++ b/nav2_core/include/nav2_core/recovery.hpp @@ -58,11 +58,6 @@ public: */ virtual void deactivate() = 0; - /** - * @brief Method to shutdown recovery and any threads involved in execution. - */ - virtual void shutdown() = 0; - /** * @brief Method Execute recovery behavior * @param name The name of this planner diff --git a/nav2_dwb_controller/dwb_controller/include/dwb_controller/dwb_controller.hpp b/nav2_dwb_controller/dwb_controller/include/dwb_controller/dwb_controller.hpp index 25fa4901..c67d86a0 100644 --- a/nav2_dwb_controller/dwb_controller/include/dwb_controller/dwb_controller.hpp +++ b/nav2_dwb_controller/dwb_controller/include/dwb_controller/dwb_controller.hpp @@ -56,7 +56,7 @@ protected: // The action server callback void followPath(); - void setPlannerPath(const nav2_msgs::msg::Path & path); + void setPlannerPath(const nav_msgs::msg::Path & path); void computeAndPublishVelocity(); void updateGlobalPath(); void publishVelocity(const nav_2d_msgs::msg::Twist2DStamped & velocity); diff --git a/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp b/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp index 175a2b61..56ee2077 100644 --- a/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp +++ b/nav2_dwb_controller/dwb_controller/src/dwb_controller.cpp @@ -206,7 +206,7 @@ void DwbController::followPath() action_server_->succeeded_current(); } -void DwbController::setPlannerPath(const nav2_msgs::msg::Path & path) +void DwbController::setPlannerPath(const nav_msgs::msg::Path & path) { auto path2d = nav_2d_utils::pathToPath2D(path); diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp index 5dcac8c3..618ef0e1 100644 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp +++ b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/conversions.hpp @@ -45,7 +45,6 @@ #include "nav_msgs/msg/path.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2/convert.h" -#include "nav2_msgs/msg/path.hpp" namespace nav_2d_utils { @@ -60,7 +59,7 @@ geometry_msgs::msg::PoseStamped pose2DToPoseStamped( const geometry_msgs::msg::Pose2D & pose2d, const std::string & frame, const rclcpp::Time & stamp); nav_msgs::msg::Path posesToPath(const std::vector<geometry_msgs::msg::PoseStamped> & poses); -nav_2d_msgs::msg::Path2D pathToPath2D(const nav2_msgs::msg::Path & path); +nav_2d_msgs::msg::Path2D pathToPath2D(const nav_msgs::msg::Path & path); nav_msgs::msg::Path poses2DToPath( const std::vector<geometry_msgs::msg::Pose2D> & poses, const std::string & frame, const rclcpp::Time & stamp); diff --git a/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp b/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp index 8a6da006..b21f05bf 100644 --- a/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp +++ b/nav2_dwb_controller/nav_2d_utils/src/conversions.cpp @@ -130,12 +130,12 @@ nav_msgs::msg::Path posesToPath(const std::vector<geometry_msgs::msg::PoseStampe return path; } -nav_2d_msgs::msg::Path2D pathToPath2D(const nav2_msgs::msg::Path & path) +nav_2d_msgs::msg::Path2D pathToPath2D(const nav_msgs::msg::Path & path) { nav_2d_msgs::msg::Path2D path2d; path2d.header = path.header; for (auto & pose : path.poses) { - path2d.poses.push_back(poseToPose2D(pose)); + path2d.poses.push_back(poseToPose2D(pose.pose)); } return path2d; } diff --git a/nav2_msgs/CMakeLists.txt b/nav2_msgs/CMakeLists.txt index 2061a6f6..6e07807d 100644 --- a/nav2_msgs/CMakeLists.txt +++ b/nav2_msgs/CMakeLists.txt @@ -4,6 +4,7 @@ project(nav2_msgs) find_package(ament_cmake REQUIRED) find_package(nav2_common REQUIRED) find_package(builtin_interfaces REQUIRED) +find_package(nav_msgs REQUIRED) find_package(geometry_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(std_msgs REQUIRED) @@ -14,7 +15,6 @@ nav2_package() rosidl_generate_interfaces(${PROJECT_NAME} "msg/Costmap.msg" "msg/CostmapMetaData.msg" - "msg/Path.msg" "msg/VoxelGrid.msg" "srv/GetCostmap.srv" "srv/ClearCostmapExceptRegion.srv" @@ -28,7 +28,7 @@ rosidl_generate_interfaces(${PROJECT_NAME} "action/Spin.action" "action/DummyRecovery.action" "action/RandomCrawl.action" - DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs + DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs nav_msgs ) ament_export_dependencies(rosidl_default_runtime) diff --git a/nav2_msgs/action/ComputePathToPose.action b/nav2_msgs/action/ComputePathToPose.action index 4af3b3da..0a6b62ee 100644 --- a/nav2_msgs/action/ComputePathToPose.action +++ b/nav2_msgs/action/ComputePathToPose.action @@ -2,6 +2,6 @@ geometry_msgs/PoseStamped pose --- #result definition -nav2_msgs/Path path +nav_msgs/Path path --- #feedback diff --git a/nav2_msgs/action/FollowPath.action b/nav2_msgs/action/FollowPath.action index 33487826..b73cbf3a 100644 --- a/nav2_msgs/action/FollowPath.action +++ b/nav2_msgs/action/FollowPath.action @@ -1,5 +1,5 @@ #goal definition -nav2_msgs/Path path +nav_msgs/Path path --- #result definition std_msgs/Empty result diff --git a/nav2_msgs/msg/Path.msg b/nav2_msgs/msg/Path.msg deleted file mode 100644 index 5a096b91..00000000 --- a/nav2_msgs/msg/Path.msg +++ /dev/null @@ -1,4 +0,0 @@ -std_msgs/Header header - -# An array of poses that represents a Path for a robot to follow -geometry_msgs/Pose[] poses \ No newline at end of file diff --git a/nav2_msgs/package.xml b/nav2_msgs/package.xml index 1b3c725d..76217cce 100644 --- a/nav2_msgs/package.xml +++ b/nav2_msgs/package.xml @@ -18,6 +18,7 @@ <depend>rosidl_default_generators</depend> <depend>geometry_msgs</depend> <depend>action_msgs</depend> + <depend>nav_msgs</depend> <test_depend>ament_lint_common</test_depend> <test_depend>ament_lint_auto</test_depend> diff --git a/nav2_navfn_planner/CMakeLists.txt b/nav2_navfn_planner/CMakeLists.txt index 4949da40..8b7271ec 100644 --- a/nav2_navfn_planner/CMakeLists.txt +++ b/nav2_navfn_planner/CMakeLists.txt @@ -9,6 +9,7 @@ find_package(rclcpp_lifecycle REQUIRED) find_package(std_msgs REQUIRED) find_package(visualization_msgs REQUIRED) find_package(nav2_util REQUIRED) +find_package(nav2_core REQUIRED) find_package(nav2_msgs REQUIRED) find_package(nav_msgs REQUIRED) find_package(geometry_msgs REQUIRED) diff --git a/nav2_system_tests/src/planning/planner_tester.hpp b/nav2_system_tests/src/planning/planner_tester.hpp index 5dfacacd..29be48d0 100644 --- a/nav2_system_tests/src/planning/planner_tester.hpp +++ b/nav2_system_tests/src/planning/planner_tester.hpp @@ -73,7 +73,7 @@ public: bool createPath( const geometry_msgs::msg::PoseStamped & goal, - nav2_msgs::msg::Path & path) + nav_msgs::msg::Path & path) { geometry_msgs::msg::PoseStamped start; if (!nav2_util::getCurrentPose(start, *tf_, "map", "base_link", 0.1)) { @@ -115,7 +115,7 @@ class PlannerTester : public rclcpp::Node, public ::testing::Test { public: using ComputePathToPoseCommand = geometry_msgs::msg::PoseStamped; - using ComputePathToPoseResult = nav2_msgs::msg::Path; + using ComputePathToPoseResult = nav_msgs::msg::Path; PlannerTester(); ~PlannerTester(); diff --git a/nav2_system_tests/src/planning/test_planner_costmaps_node.cpp b/nav2_system_tests/src/planning/test_planner_costmaps_node.cpp index 6d43a1c5..b12889a1 100644 --- a/nav2_system_tests/src/planning/test_planner_costmaps_node.cpp +++ b/nav2_system_tests/src/planning/test_planner_costmaps_node.cpp @@ -26,7 +26,7 @@ using nav2_system_tests::PlannerTester; using nav2_util::TestCostmap; using ComputePathToPoseCommand = geometry_msgs::msg::PoseStamped; -using ComputePathToPoseResult = nav2_msgs::msg::Path; +using ComputePathToPoseResult = nav_msgs::msg::Path; // rclcpp::init can only be called once per process, so this needs to be a global variable class RclCppFixture diff --git a/nav2_system_tests/src/planning/test_planner_random_node.cpp b/nav2_system_tests/src/planning/test_planner_random_node.cpp index 51c60ac5..f37d6d81 100644 --- a/nav2_system_tests/src/planning/test_planner_random_node.cpp +++ b/nav2_system_tests/src/planning/test_planner_random_node.cpp @@ -26,7 +26,7 @@ using nav2_system_tests::PlannerTester; using nav2_util::TestCostmap; using ComputePathToPoseCommand = geometry_msgs::msg::PoseStamped; -using ComputePathToPoseResult = nav2_msgs::msg::Path; +using ComputePathToPoseResult = nav_msgs::msg::Path; // rclcpp::init can only be called once per process, so this needs to be a global variable class RclCppFixture -- GitLab