Skip to content

Commit 60b495c

Browse files
authored
Sync changes with nav2 (#120)
Signed-off-by: mini-1235 <[email protected]>
1 parent d895fd5 commit 60b495c

File tree

10 files changed

+86
-23
lines changed

10 files changed

+86
-23
lines changed

nav2_gradient_costmap_plugin/CMakeLists.txt

Lines changed: 8 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,5 +48,12 @@ install(TARGETS ${lib_name}
4848
# file into "share" directory and sets ament indexes for it.
4949
# This allows the plugin to be discovered as a plugin of required type.
5050
pluginlib_export_plugin_description_file(nav2_costmap_2d gradient_layer.xml)
51-
ament_target_dependencies(${lib_name} ${dep_pkgs})
51+
target_link_libraries(nav2_gradient_costmap_plugin_core PUBLIC
52+
nav2_costmap_2d::filters
53+
nav2_costmap_2d::layers
54+
nav2_costmap_2d::nav2_costmap_2d_client
55+
nav2_costmap_2d::nav2_costmap_2d_core
56+
pluginlib::pluginlib
57+
rclcpp::rclcpp
58+
)
5259
ament_package()

nav2_pure_pursuit_controller/CMakeLists.txt

Lines changed: 15 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@ find_package(geometry_msgs REQUIRED)
1111
find_package(nav_msgs REQUIRED)
1212
find_package(pluginlib REQUIRED)
1313
find_package(tf2 REQUIRED)
14+
find_package(nav2_ros_common REQUIRED)
1415

1516
nav2_package()
1617

@@ -27,6 +28,7 @@ set(dependencies
2728
nav2_util
2829
nav2_core
2930
tf2
31+
nav2_ros_common
3032
)
3133

3234
add_library(nav2_pure_pursuit_controller SHARED
@@ -35,8 +37,19 @@ add_library(nav2_pure_pursuit_controller SHARED
3537
# prevent pluginlib from using boost
3638
target_compile_definitions(nav2_pure_pursuit_controller PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
3739

38-
ament_target_dependencies(nav2_pure_pursuit_controller
39-
${dependencies}
40+
target_link_libraries(nav2_pure_pursuit_controller PUBLIC
41+
${geometry_msgs_TARGETS}
42+
${nav_msgs_TARGETS}
43+
nav2_core::nav2_core
44+
nav2_costmap_2d::filters
45+
nav2_costmap_2d::layers
46+
nav2_costmap_2d::nav2_costmap_2d_client
47+
nav2_costmap_2d::nav2_costmap_2d_core
48+
nav2_ros_common::nav2_ros_common
49+
nav2_util::nav2_util_core
50+
pluginlib::pluginlib
51+
rclcpp::rclcpp
52+
tf2::tf2
4053
)
4154

4255
install(TARGETS nav2_pure_pursuit_controller

nav2_pure_pursuit_controller/include/nav2_pure_pursuit_controller/pure_pursuit_controller.hpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616
#include "rclcpp/rclcpp.hpp"
1717
#include "pluginlib/class_loader.hpp"
1818
#include "pluginlib/class_list_macros.hpp"
19+
#include "nav2_ros_common/lifecycle_node.hpp"
20+
#include "nav2_ros_common/node_utils.hpp"
1921

2022
namespace nav2_pure_pursuit_controller
2123
{
@@ -27,7 +29,7 @@ class PurePursuitController : public nav2_core::Controller
2729
~PurePursuitController() override = default;
2830

2931
void configure(
30-
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
32+
const nav2::LifecycleNode::WeakPtr & parent,
3133
std::string name, const std::shared_ptr<tf2_ros::Buffer> tf,
3234
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
3335

@@ -55,7 +57,7 @@ class PurePursuitController : public nav2_core::Controller
5557
const rclcpp::Duration & transform_tolerance
5658
) const;
5759

58-
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
60+
nav2::LifecycleNode::WeakPtr node_;
5961
std::shared_ptr<tf2_ros::Buffer> tf_;
6062
std::string plugin_name_;
6163
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
@@ -68,7 +70,7 @@ class PurePursuitController : public nav2_core::Controller
6870
rclcpp::Duration transform_tolerance_ {0, 0};
6971

7072
nav_msgs::msg::Path global_plan_;
71-
std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>> global_pub_;
73+
std::shared_ptr<nav2::Publisher<nav_msgs::msg::Path>> global_pub_;
7274
};
7375

7476
} // namespace nav2_pure_pursuit_controller

nav2_pure_pursuit_controller/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
<depend>nav2_msgs</depend>
1919
<depend>pluginlib</depend>
2020
<depend>tf2</depend>
21+
<depend>nav2_ros_common</depend>
2122

2223
<exec_depend>nav2_bringup</exec_depend>
2324

nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,15 +12,14 @@
1212

1313
#include "nav2_core/controller_exceptions.hpp"
1414
#include "nav2_core/planner_exceptions.hpp"
15-
#include "nav2_util/node_utils.hpp"
1615
#include "nav2_pure_pursuit_controller/pure_pursuit_controller.hpp"
1716
#include "nav2_util/geometry_utils.hpp"
1817

1918
using std::hypot;
2019
using std::min;
2120
using std::max;
2221
using std::abs;
23-
using nav2_util::declare_parameter_if_not_declared;
22+
using nav2::declare_parameter_if_not_declared;
2423
using nav2_util::geometry_utils::euclidean_distance;
2524

2625
namespace nav2_pure_pursuit_controller
@@ -48,7 +47,7 @@ Iter min_by(Iter begin, Iter end, Getter getCompareVal)
4847
}
4948

5049
void PurePursuitController::configure(
51-
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
50+
const nav2::LifecycleNode::WeakPtr & parent,
5251
std::string name, const std::shared_ptr<tf2_ros::Buffer> tf,
5352
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
5453
{

nav2_sms_behavior/CMakeLists.txt

Lines changed: 27 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -62,13 +62,34 @@ add_library(${library_name} SHARED
6262

6363
target_compile_definitions(${library_name} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
6464

65-
ament_target_dependencies(${library_name}
66-
${dependencies}
67-
)
68-
6965
rosidl_get_typesupport_target(cpp_typesupport_target ${PROJECT_NAME} "rosidl_typesupport_cpp")
70-
target_link_libraries(${library_name} "${cpp_typesupport_target}")
71-
66+
target_link_libraries(nav2_sms_behavior_plugin PUBLIC
67+
${builtin_interfaces_TARGETS}
68+
${geometry_msgs_TARGETS}
69+
${nav2_msgs_TARGETS}
70+
${nav_msgs_TARGETS}
71+
${std_msgs_TARGETS}
72+
${visualization_msgs_TARGETS}
73+
nav2_behaviors::behavior_server_core
74+
nav2_behaviors::nav2_assisted_teleop_behavior
75+
nav2_behaviors::nav2_back_up_behavior
76+
nav2_behaviors::nav2_drive_on_heading_behavior
77+
nav2_behaviors::nav2_spin_behavior
78+
nav2_behaviors::nav2_wait_behavior
79+
nav2_core::nav2_core
80+
nav2_costmap_2d::filters
81+
nav2_costmap_2d::layers
82+
nav2_costmap_2d::nav2_costmap_2d_client
83+
nav2_costmap_2d::nav2_costmap_2d_core
84+
nav2_util::nav2_util_core
85+
pluginlib::pluginlib
86+
rclcpp::rclcpp
87+
rclcpp_action::rclcpp_action
88+
rclcpp_lifecycle::rclcpp_lifecycle
89+
tf2_ros::static_transform_broadcaster_node
90+
tf2_ros::tf2_ros
91+
${cpp_typesupport_target}
92+
)
7293

7394
pluginlib_export_plugin_description_file(nav2_core behavior_plugin.xml)
7495

nav2_straightline_planner/CMakeLists.txt

Lines changed: 21 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ find_package(tf2_ros REQUIRED)
2424
find_package(nav2_costmap_2d REQUIRED)
2525
find_package(nav2_core REQUIRED)
2626
find_package(pluginlib REQUIRED)
27+
find_package(nav2_ros_common)
2728

2829
include_directories(
2930
include
@@ -46,14 +47,32 @@ set(dependencies
4647
nav2_costmap_2d
4748
nav2_core
4849
pluginlib
50+
nav2_ros_common
4951
)
5052

5153
add_library(${library_name} SHARED
5254
src/straight_line_planner.cpp
5355
)
5456

55-
ament_target_dependencies(${library_name}
56-
${dependencies}
57+
target_link_libraries(nav2_straightline_planner_plugin PUBLIC
58+
${builtin_interfaces_TARGETS}
59+
${geometry_msgs_TARGETS}
60+
${nav2_msgs_TARGETS}
61+
${nav_msgs_TARGETS}
62+
${std_msgs_TARGETS}
63+
${visualization_msgs_TARGETS}
64+
nav2_core::nav2_core
65+
nav2_costmap_2d::filters
66+
nav2_costmap_2d::layers
67+
nav2_costmap_2d::nav2_costmap_2d_client
68+
nav2_costmap_2d::nav2_costmap_2d_core
69+
nav2_util::nav2_util_core
70+
nav2_ros_common::nav2_ros_common
71+
pluginlib::pluginlib
72+
rclcpp::rclcpp
73+
rclcpp_action::rclcpp_action
74+
rclcpp_lifecycle::rclcpp_lifecycle
75+
tf2_ros::tf2_ros
5776
)
5877

5978
target_compile_definitions(${library_name} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")

nav2_straightline_planner/include/nav2_straightline_planner/straight_line_planner.hpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,8 @@
5151
#include "nav2_core/global_planner.hpp"
5252
#include "nav_msgs/msg/path.hpp"
5353
#include "nav2_util/robot_utils.hpp"
54-
#include "nav2_util/lifecycle_node.hpp"
54+
#include "nav2_ros_common/lifecycle_node.hpp"
55+
#include "nav2_ros_common/node_utils.hpp"
5556
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
5657

5758
namespace nav2_straightline_planner
@@ -65,7 +66,7 @@ class StraightLine : public nav2_core::GlobalPlanner
6566

6667
// plugin configure
6768
void configure(
68-
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
69+
const nav2::LifecycleNode::WeakPtr & parent,
6970
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
7071
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
7172

@@ -89,7 +90,7 @@ class StraightLine : public nav2_core::GlobalPlanner
8990
std::shared_ptr<tf2_ros::Buffer> tf_;
9091

9192
// node ptr
92-
nav2_util::LifecycleNode::SharedPtr node_;
93+
nav2::LifecycleNode::SharedPtr node_;
9394

9495
// Global Costmap
9596
nav2_costmap_2d::Costmap2D * costmap_;

nav2_straightline_planner/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<depend>nav2_costmap_2d</depend>
2424
<depend>nav2_core</depend>
2525
<depend>pluginlib</depend>
26+
<depend>nav2_ros_common</depend>
2627

2728
<test_depend>ament_lint_auto</test_depend>
2829
<test_depend>ament_lint_common</test_depend>

nav2_straightline_planner/src/straight_line_planner.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -41,15 +41,14 @@
4141
#include <cmath>
4242
#include <string>
4343
#include <memory>
44-
#include "nav2_util/node_utils.hpp"
4544

4645
#include "nav2_straightline_planner/straight_line_planner.hpp"
4746

4847
namespace nav2_straightline_planner
4948
{
5049

5150
void StraightLine::configure(
52-
const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
51+
const nav2::LifecycleNode::WeakPtr & parent,
5352
std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
5453
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
5554
{
@@ -60,7 +59,7 @@ void StraightLine::configure(
6059
global_frame_ = costmap_ros->getGlobalFrameID();
6160

6261
// Parameter initialization
63-
nav2_util::declare_parameter_if_not_declared(
62+
nav2::declare_parameter_if_not_declared(
6463
node_, name_ + ".interpolation_resolution", rclcpp::ParameterValue(
6564
0.1));
6665
node_->get_parameter(name_ + ".interpolation_resolution", interpolation_resolution_);

0 commit comments

Comments
 (0)