diff --git a/.circleci/config.yml b/.circleci/config.yml index bab7710d374..d6766347816 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -33,12 +33,12 @@ _commands: - restore_cache: name: Restore Cache << parameters.key >> keys: - - "<< parameters.key >>-v35\ + - "<< parameters.key >>-v36\ -{{ arch }}\ -{{ .Branch }}\ -{{ .Environment.CIRCLE_PR_NUMBER }}\ -{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}" - - "<< parameters.key >>-v35\ + - "<< parameters.key >>-v36\ -{{ arch }}\ -main\ -\ @@ -58,7 +58,7 @@ _commands: steps: - save_cache: name: Save Cache << parameters.key >> - key: "<< parameters.key >>-v35\ + key: "<< parameters.key >>-v36\ -{{ arch }}\ -{{ .Branch }}\ -{{ .Environment.CIRCLE_PR_NUMBER }}\ diff --git a/nav2_amcl/CMakeLists.txt b/nav2_amcl/CMakeLists.txt index 3cb30254fa3..267b81513f4 100644 --- a/nav2_amcl/CMakeLists.txt +++ b/nav2_amcl/CMakeLists.txt @@ -17,6 +17,7 @@ find_package(std_srvs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -38,7 +39,8 @@ add_library(pf_lib SHARED target_include_directories(pf_lib PUBLIC "$" - "$") + "$" + "$") if(HAVE_DRAND48) target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48") endif() @@ -52,7 +54,8 @@ add_library(map_lib SHARED target_include_directories(map_lib PUBLIC "$" - "$") + "$" + "$") add_library(motions_lib SHARED src/motion_model/omni_motion_model.cpp @@ -61,7 +64,8 @@ add_library(motions_lib SHARED target_include_directories(motions_lib PUBLIC "$" - "$") + "$" + "$") target_link_libraries(motions_lib PUBLIC pf_lib pluginlib::pluginlib @@ -77,7 +81,8 @@ add_library(sensors_lib SHARED target_include_directories(sensors_lib PUBLIC "$" - "$") + "$" + "$") target_link_libraries(sensors_lib PUBLIC pf_lib map_lib @@ -96,7 +101,8 @@ endif() target_include_directories(${library_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} message_filters::message_filters @@ -123,7 +129,8 @@ add_executable(${executable_name} target_include_directories(${executable_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${executable_name} PRIVATE ${library_name} ) @@ -169,6 +176,7 @@ ament_export_dependencies( std_srvs tf2 tf2_ros + nav2_ros_common ) ament_export_targets(${library_name}) pluginlib_export_plugin_description_file(nav2_amcl plugins.xml) diff --git a/nav2_amcl/include/nav2_amcl/amcl_node.hpp b/nav2_amcl/include/nav2_amcl/amcl_node.hpp index 58b48246a9d..0be08c39db6 100644 --- a/nav2_amcl/include/nav2_amcl/amcl_node.hpp +++ b/nav2_amcl/include/nav2_amcl/amcl_node.hpp @@ -32,7 +32,7 @@ #include "rclcpp/version.h" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_amcl/motion_model/motion_model.hpp" #include "nav2_amcl/sensors/laser/laser.hpp" #include "nav2_msgs/msg/particle.hpp" @@ -42,7 +42,7 @@ #include "pluginlib/class_loader.hpp" #include "rclcpp/node_options.hpp" #include "sensor_msgs/msg/laser_scan.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/service_server.hpp" #include "std_srvs/srv/empty.hpp" #include "tf2_ros/message_filter.h" #include "tf2_ros/transform_broadcaster.h" @@ -56,7 +56,7 @@ namespace nav2_amcl * @class AmclNode * @brief ROS wrapper for AMCL */ -class AmclNode : public nav2_util::LifecycleNode +class AmclNode : public nav2::LifecycleNode { public: /* @@ -73,23 +73,23 @@ class AmclNode : public nav2_util::LifecycleNode /* * @brief Lifecycle configure */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /* * @brief Lifecycle activate */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /* * @brief Lifecycle deactivate */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /* * @brief Lifecycle cleanup */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /* * @brief Lifecycle shutdown */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** * @brief Callback executed when a parameter change is detected @@ -109,7 +109,7 @@ class AmclNode : public nav2_util::LifecycleNode // in order to isolate TF timer used in message filter. rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; - std::unique_ptr executor_thread_; + std::unique_ptr executor_thread_; // Pose hypothesis typedef struct @@ -149,7 +149,7 @@ class AmclNode : public nav2_util::LifecycleNode std::atomic first_map_received_{false}; amcl_hyp_t * initial_pose_hyp_; std::recursive_mutex mutex_; - rclcpp::Subscription::ConstSharedPtr map_sub_; + nav2::Subscription::ConstSharedPtr map_sub_; #if NEW_UNIFORM_SAMPLING struct Point2D { int32_t x; int32_t y; }; static std::vector free_space_indices; @@ -180,6 +180,7 @@ class AmclNode : public nav2_util::LifecycleNode std::unique_ptr> laser_scan_sub_; #endif + std::unique_ptr> laser_scan_filter_; message_filters::Connection laser_scan_connection_; @@ -188,11 +189,11 @@ class AmclNode : public nav2_util::LifecycleNode * @brief Initialize pub subs of AMCL */ void initPubSub(); - rclcpp::Subscription::ConstSharedPtr + nav2::Subscription::ConstSharedPtr initial_pose_sub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr pose_pub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr particle_cloud_pub_; /* * @brief Handle with an initial pose estimate is received @@ -208,8 +209,7 @@ class AmclNode : public nav2_util::LifecycleNode * @brief Initialize state services */ void initServices(); - nav2_util::ServiceServer>::SharedPtr global_loc_srv_; + nav2::ServiceServer::SharedPtr global_loc_srv_; /* * @brief Service callback for a global relocalization request */ @@ -219,8 +219,7 @@ class AmclNode : public nav2_util::LifecycleNode std::shared_ptr response); // service server for providing an initial pose guess - nav2_util::ServiceServer>::SharedPtr initial_guess_srv_; + nav2::ServiceServer::SharedPtr initial_guess_srv_; /* * @brief Service callback for an initial pose guess request */ @@ -230,8 +229,7 @@ class AmclNode : public nav2_util::LifecycleNode std::shared_ptr response); // Let amcl update samples without requiring motion - nav2_util::ServiceServer>::SharedPtr nomotion_update_srv_; + nav2::ServiceServer::SharedPtr nomotion_update_srv_; /* * @brief Request an AMCL update even though the robot hasn't moved */ diff --git a/nav2_amcl/package.xml b/nav2_amcl/package.xml index d7af79e860b..c1a2cbc2cea 100644 --- a/nav2_amcl/package.xml +++ b/nav2_amcl/package.xml @@ -38,6 +38,7 @@ tf2 tf2_geometry_msgs tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_amcl/src/amcl_node.cpp b/nav2_amcl/src/amcl_node.cpp index 953e5e05509..7fa70df770f 100644 --- a/nav2_amcl/src/amcl_node.cpp +++ b/nav2_amcl/src/amcl_node.cpp @@ -45,7 +45,7 @@ #include "tf2_ros/create_timer_ros.h" #include "nav2_amcl/portable_utils.hpp" -#include "nav2_util/validate_messages.hpp" +#include "nav2_ros_common/validate_messages.hpp" using rcl_interfaces::msg::ParameterType; using namespace std::chrono_literals; @@ -55,185 +55,136 @@ namespace nav2_amcl using nav2_util::geometry_utils::orientationAroundZAxis; AmclNode::AmclNode(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("amcl", "", options) +: nav2::LifecycleNode("amcl", "", options) { RCLCPP_INFO(get_logger(), "Creating"); - add_parameter( - "alpha1", rclcpp::ParameterValue(0.2), - "This is the alpha1 parameter", "These are additional constraints for alpha1"); - - add_parameter( - "alpha2", rclcpp::ParameterValue(0.2), - "This is the alpha2 parameter", "These are additional constraints for alpha2"); - - add_parameter( - "alpha3", rclcpp::ParameterValue(0.2), - "This is the alpha3 parameter", "These are additional constraints for alpha3"); - - add_parameter( - "alpha4", rclcpp::ParameterValue(0.2), - "This is the alpha4 parameter", "These are additional constraints for alpha4"); - - add_parameter( - "alpha5", rclcpp::ParameterValue(0.2), - "This is the alpha5 parameter", "These are additional constraints for alpha5"); - - add_parameter( - "base_frame_id", rclcpp::ParameterValue(std::string("base_footprint")), - "Which frame to use for the robot base"); - - add_parameter("beam_skip_distance", rclcpp::ParameterValue(0.5)); - add_parameter("beam_skip_error_threshold", rclcpp::ParameterValue(0.9)); - add_parameter("beam_skip_threshold", rclcpp::ParameterValue(0.3)); - add_parameter("do_beamskip", rclcpp::ParameterValue(false)); - - add_parameter( - "global_frame_id", rclcpp::ParameterValue(std::string("map")), - "The name of the coordinate frame published by the localization system"); - - add_parameter( - "lambda_short", rclcpp::ParameterValue(0.1), - "Exponential decay parameter for z_short part of model"); - - add_parameter( - "laser_likelihood_max_dist", rclcpp::ParameterValue(2.0), - "Maximum distance to do obstacle inflation on map, for use in likelihood_field model"); - - add_parameter( - "laser_max_range", rclcpp::ParameterValue(100.0), - "Maximum scan range to be considered", - "-1.0 will cause the laser's reported maximum range to be used"); - - add_parameter( - "laser_min_range", rclcpp::ParameterValue(-1.0), - "Minimum scan range to be considered", - "-1.0 will cause the laser's reported minimum range to be used"); - - add_parameter( - "laser_model_type", rclcpp::ParameterValue(std::string("likelihood_field")), - "Which model to use, either beam, likelihood_field, or likelihood_field_prob", - "Same as likelihood_field but incorporates the beamskip feature, if enabled"); - - add_parameter( - "set_initial_pose", rclcpp::ParameterValue(false), - "Causes AMCL to set initial pose from the initial_pose* parameters instead of " - "waiting for the initial_pose message"); - - add_parameter( - "initial_pose.x", rclcpp::ParameterValue(0.0), - "X coordinate of the initial robot pose in the map frame"); - - add_parameter( - "initial_pose.y", rclcpp::ParameterValue(0.0), - "Y coordinate of the initial robot pose in the map frame"); - - add_parameter( - "initial_pose.z", rclcpp::ParameterValue(0.0), - "Z coordinate of the initial robot pose in the map frame"); - - add_parameter( - "initial_pose.yaw", rclcpp::ParameterValue(0.0), - "Yaw of the initial robot pose in the map frame"); - - add_parameter( - "max_beams", rclcpp::ParameterValue(60), - "How many evenly-spaced beams in each scan to be used when updating the filter"); - - add_parameter( - "max_particles", rclcpp::ParameterValue(2000), - "Maximum allowed number of particles"); - - add_parameter( - "min_particles", rclcpp::ParameterValue(500), - "Minimum allowed number of particles"); - - add_parameter( - "odom_frame_id", rclcpp::ParameterValue(std::string("odom")), - "Which frame to use for odometry"); - - add_parameter("pf_err", rclcpp::ParameterValue(0.05)); - add_parameter("pf_z", rclcpp::ParameterValue(0.99)); - - add_parameter( - "recovery_alpha_fast", rclcpp::ParameterValue(0.0), - "Exponential decay rate for the fast average weight filter, used in deciding when to recover " - "by adding random poses", - "A good value might be 0.1"); - - add_parameter( - "recovery_alpha_slow", rclcpp::ParameterValue(0.0), - "Exponential decay rate for the slow average weight filter, used in deciding when to recover " - "by adding random poses", - "A good value might be 0.001"); - - add_parameter( - "resample_interval", rclcpp::ParameterValue(1), - "Number of filter updates required before resampling"); - - add_parameter("robot_model_type", rclcpp::ParameterValue("nav2_amcl::DifferentialMotionModel")); - - add_parameter( - "save_pose_rate", rclcpp::ParameterValue(0.5), - "Maximum rate (Hz) at which to store the last estimated pose and covariance to the parameter " - "server, in the variables ~initial_pose_* and ~initial_cov_*. This saved pose will be used " - "on subsequent runs to initialize the filter", - "-1.0 to disable"); - - add_parameter("sigma_hit", rclcpp::ParameterValue(0.2)); - - add_parameter( - "tf_broadcast", rclcpp::ParameterValue(true), - "Set this to false to prevent amcl from publishing the transform between the global frame and " - "the odometry frame"); - - add_parameter( - "transform_tolerance", rclcpp::ParameterValue(1.0), - "Time with which to post-date the transform that is published, to indicate that this transform " - "is valid into the future"); - - add_parameter( - "update_min_a", rclcpp::ParameterValue(0.2), - "Rotational movement required before performing a filter update"); - - add_parameter( - "update_min_d", rclcpp::ParameterValue(0.25), - "Translational movement required before performing a filter update"); - - add_parameter("z_hit", rclcpp::ParameterValue(0.5)); - add_parameter("z_max", rclcpp::ParameterValue(0.05)); - add_parameter("z_rand", rclcpp::ParameterValue(0.5)); - add_parameter("z_short", rclcpp::ParameterValue(0.05)); - - add_parameter( - "always_reset_initial_pose", rclcpp::ParameterValue(false), - "Requires that AMCL is provided an initial pose either via topic or initial_pose* parameter " - "(with parameter set_initial_pose: true) when reset. Otherwise, by default AMCL will use the" - "last known pose to initialize"); - - add_parameter( - "scan_topic", rclcpp::ParameterValue("scan"), - "Topic to subscribe to in order to receive the laser scan for localization"); - - add_parameter( - "map_topic", rclcpp::ParameterValue("map"), - "Topic to subscribe to in order to receive the map to localize on"); - - add_parameter( - "first_map_only", rclcpp::ParameterValue(false), - "Set this to true, when you want to load a new map published from the map_server"); - - add_parameter( - "freespace_downsampling", rclcpp::ParameterValue( - false), - "Downsample the free space used by the Pose Generator. Use it with large maps to save memory"); + declare_parameter( + "alpha1", rclcpp::ParameterValue(0.2)); + + declare_parameter( + "alpha2", rclcpp::ParameterValue(0.2)); + + declare_parameter( + "alpha3", rclcpp::ParameterValue(0.2)); + + declare_parameter( + "alpha4", rclcpp::ParameterValue(0.2)); + + declare_parameter( + "alpha5", rclcpp::ParameterValue(0.2)); + + declare_parameter( + "base_frame_id", rclcpp::ParameterValue(std::string("base_footprint"))); + + declare_parameter("beam_skip_distance", rclcpp::ParameterValue(0.5)); + declare_parameter("beam_skip_error_threshold", rclcpp::ParameterValue(0.9)); + declare_parameter("beam_skip_threshold", rclcpp::ParameterValue(0.3)); + declare_parameter("do_beamskip", rclcpp::ParameterValue(false)); + + declare_parameter( + "global_frame_id", rclcpp::ParameterValue(std::string("map"))); + + declare_parameter( + "lambda_short", rclcpp::ParameterValue(0.1)); + + declare_parameter( + "laser_likelihood_max_dist", rclcpp::ParameterValue(2.0)); + + declare_parameter( + "laser_max_range", rclcpp::ParameterValue(100.0)); + + declare_parameter( + "laser_min_range", rclcpp::ParameterValue(-1.0)); + + declare_parameter( + "laser_model_type", rclcpp::ParameterValue(std::string("likelihood_field"))); + + declare_parameter( + "set_initial_pose", rclcpp::ParameterValue(false)); + + declare_parameter( + "initial_pose.x", rclcpp::ParameterValue(0.0)); + + declare_parameter( + "initial_pose.y", rclcpp::ParameterValue(0.0)); + + declare_parameter( + "initial_pose.z", rclcpp::ParameterValue(0.0)); + + declare_parameter( + "initial_pose.yaw", rclcpp::ParameterValue(0.0)); + + declare_parameter( + "max_beams", rclcpp::ParameterValue(60)); + + declare_parameter( + "max_particles", rclcpp::ParameterValue(2000)); + + declare_parameter( + "min_particles", rclcpp::ParameterValue(500)); + + declare_parameter( + "odom_frame_id", rclcpp::ParameterValue(std::string("odom"))); + + declare_parameter("pf_err", rclcpp::ParameterValue(0.05)); + declare_parameter("pf_z", rclcpp::ParameterValue(0.99)); + + declare_parameter( + "recovery_alpha_fast", rclcpp::ParameterValue(0.0)); + + declare_parameter( + "recovery_alpha_slow", rclcpp::ParameterValue(0.0)); + + declare_parameter( + "resample_interval", rclcpp::ParameterValue(1)); + + declare_parameter("robot_model_type", + rclcpp::ParameterValue("nav2_amcl::DifferentialMotionModel")); + + declare_parameter( + "save_pose_rate", rclcpp::ParameterValue(0.5)); + + declare_parameter("sigma_hit", rclcpp::ParameterValue(0.2)); + + declare_parameter( + "tf_broadcast", rclcpp::ParameterValue(true)); + + declare_parameter( + "transform_tolerance", rclcpp::ParameterValue(1.0)); + + declare_parameter( + "update_min_a", rclcpp::ParameterValue(0.2)); + + declare_parameter( + "update_min_d", rclcpp::ParameterValue(0.25)); + + declare_parameter("z_hit", rclcpp::ParameterValue(0.5)); + declare_parameter("z_max", rclcpp::ParameterValue(0.05)); + declare_parameter("z_rand", rclcpp::ParameterValue(0.5)); + declare_parameter("z_short", rclcpp::ParameterValue(0.05)); + + declare_parameter( + "always_reset_initial_pose", rclcpp::ParameterValue(false)); + + declare_parameter( + "scan_topic", rclcpp::ParameterValue("scan")); + + declare_parameter( + "map_topic", rclcpp::ParameterValue("map")); + + declare_parameter( + "first_map_only", rclcpp::ParameterValue(false)); + + declare_parameter( + "freespace_downsampling", rclcpp::ParameterValue(false)); } AmclNode::~AmclNode() { } -nav2_util::CallbackReturn +nav2::CallbackReturn AmclNode::on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -249,11 +200,11 @@ AmclNode::on_configure(const rclcpp_lifecycle::State & /*state*/) initOdometry(); executor_ = std::make_shared(); executor_->add_callback_group(callback_group_, get_node_base_interface()); - executor_thread_ = std::make_unique(executor_); - return nav2_util::CallbackReturn::SUCCESS; + executor_thread_ = std::make_unique(executor_); + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn AmclNode::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -293,10 +244,10 @@ AmclNode::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn AmclNode::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -314,10 +265,10 @@ AmclNode::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -384,14 +335,14 @@ AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/) rclcpp::ParameterValue(tf2::getYaw(last_published_pose_.pose.pose.orientation)))); } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn AmclNode::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool @@ -416,7 +367,7 @@ AmclNode::getOdomPose( { // Get the robot's pose geometry_msgs::msg::PoseStamped ident; - ident.header.frame_id = nav2_util::strip_leading_slash(frame_id); + ident.header.frame_id = frame_id; ident.header.stamp = sensor_timestamp; tf2::toMsg(tf2::Transform::getIdentity(), ident.pose); @@ -524,15 +475,15 @@ AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::Sha RCLCPP_INFO(get_logger(), "initialPoseReceived"); - if (!nav2_util::validateMsg(*msg)) { + if (!nav2::validateMsg(*msg)) { RCLCPP_ERROR(get_logger(), "Received initialpose message is malformed. Rejecting."); return; } - if (nav2_util::strip_leading_slash(msg->header.frame_id) != global_frame_id_) { + if (msg->header.frame_id != global_frame_id_) { RCLCPP_WARN( get_logger(), "Ignoring initial pose in frame \"%s\"; initial poses must be in the global frame, \"%s\"", - nav2_util::strip_leading_slash(msg->header.frame_id).c_str(), + msg->header.frame_id.c_str(), global_frame_id_.c_str()); return; } @@ -638,7 +589,7 @@ AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan) return; } - std::string laser_scan_frame_id = nav2_util::strip_leading_slash(laser_scan->header.frame_id); + std::string laser_scan_frame_id = laser_scan->header.frame_id; last_laser_received_ts_ = now(); int laser_index = -1; geometry_msgs::msg::PoseStamped laser_pose; @@ -802,7 +753,7 @@ bool AmclNode::updateFilter( // Here we set the roll pitch yaw of the lasers. We assume roll and pitch are zero. geometry_msgs::msg::QuaternionStamped min_q, inc_q; min_q.header.stamp = laser_scan->header.stamp; - min_q.header.frame_id = nav2_util::strip_leading_slash(laser_scan->header.frame_id); + min_q.header.frame_id = laser_scan->header.frame_id; min_q.quaternion = orientationAroundZAxis(laser_scan->angle_min); inc_q.header = min_q.header; @@ -1111,11 +1062,6 @@ AmclNode::initParameters() save_pose_period_ = tf2::durationFromSec(1.0 / save_pose_rate); transform_tolerance_ = tf2::durationFromSec(tmp_tol); - - odom_frame_id_ = nav2_util::strip_leading_slash(odom_frame_id_); - base_frame_id_ = nav2_util::strip_leading_slash(base_frame_id_); - global_frame_id_ = nav2_util::strip_leading_slash(global_frame_id_); - last_time_printed_msg_ = now(); // Semantic checks @@ -1389,8 +1335,9 @@ AmclNode::dynamicParametersCallback( if (reinit_map) { map_sub_.reset(); map_sub_ = create_subscription( - map_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&AmclNode::mapReceived, this, std::placeholders::_1)); + map_topic_, + std::bind(&AmclNode::mapReceived, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); } result.successful = true; @@ -1401,7 +1348,7 @@ void AmclNode::mapReceived(const nav_msgs::msg::OccupancyGrid::SharedPtr msg) { RCLCPP_DEBUG(get_logger(), "AmclNode: A new map was received."); - if (!nav2_util::validateMsg(*msg)) { + if (!nav2::validateMsg(*msg)) { RCLCPP_ERROR(get_logger(), "Received map message is malformed. Rejecting."); return; } @@ -1526,11 +1473,12 @@ AmclNode::initMessageFilters() #if RCLCPP_VERSION_GTE(29, 6, 0) laser_scan_sub_ = std::make_unique>( - shared_from_this(), scan_topic_, rclcpp::SensorDataQoS(), sub_opt); + shared_from_this(), scan_topic_, nav2::qos::SensorDataQoS(), sub_opt); #else laser_scan_sub_ = std::make_unique>( - shared_from_this(), scan_topic_, rmw_qos_profile_sensor_data, sub_opt); + std::static_pointer_cast(shared_from_this()), + scan_topic_, nav2::qos::SensorDataQoS().get_rmw_qos_profile(), sub_opt); #endif laser_scan_filter_ = std::make_unique>( @@ -1541,9 +1489,7 @@ AmclNode::initMessageFilters() laser_scan_connection_ = laser_scan_filter_->registerCallback( - std::bind( - &AmclNode::laserReceived, - this, std::placeholders::_1)); + std::bind(&AmclNode::laserReceived, this, std::placeholders::_1)); } void @@ -1553,19 +1499,20 @@ AmclNode::initPubSub() particle_cloud_pub_ = create_publisher( "particle_cloud", - rclcpp::SensorDataQoS()); + nav2::qos::SensorDataQoS()); pose_pub_ = create_publisher( "amcl_pose", - rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + nav2::qos::LatchedPublisherQoS()); initial_pose_sub_ = create_subscription( - "initialpose", rclcpp::SystemDefaultsQoS(), + "initialpose", std::bind(&AmclNode::initialPoseReceived, this, std::placeholders::_1)); map_sub_ = create_subscription( - map_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&AmclNode::mapReceived, this, std::placeholders::_1)); + map_topic_, + std::bind(&AmclNode::mapReceived, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); RCLCPP_INFO(get_logger(), "Subscribed to map topic."); } @@ -1573,21 +1520,18 @@ AmclNode::initPubSub() void AmclNode::initServices() { - global_loc_srv_ = std::make_shared>>( - "reinitialize_global_localization", shared_from_this(), + global_loc_srv_ = create_service( + "reinitialize_global_localization", std::bind(&AmclNode::globalLocalizationCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - initial_guess_srv_ = std::make_shared>>( - "set_initial_pose", shared_from_this(), + initial_guess_srv_ = create_service( + "set_initial_pose", std::bind(&AmclNode::initialPoseReceivedSrv, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - nomotion_update_srv_ = std::make_shared>>( - "request_nomotion_update", shared_from_this(), + nomotion_update_srv_ = create_service( + "request_nomotion_update", std::bind(&AmclNode::nomotionUpdateCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); } diff --git a/nav2_behavior_tree/CMakeLists.txt b/nav2_behavior_tree/CMakeLists.txt index 2a4d3ad90cf..67710be864f 100644 --- a/nav2_behavior_tree/CMakeLists.txt +++ b/nav2_behavior_tree/CMakeLists.txt @@ -17,6 +17,7 @@ find_package(std_msgs REQUIRED) find_package(std_srvs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -28,7 +29,8 @@ add_library(${library_name} SHARED target_include_directories(${library_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${library_name} PUBLIC ${action_msgs_TARGETS} behaviortree_cpp::behaviortree_cpp @@ -246,7 +248,8 @@ foreach(bt_plugin ${plugin_libs}) target_include_directories(${bt_plugin} PRIVATE "$" - "$") + "$" + "$") target_link_libraries(${bt_plugin} PUBLIC behaviortree_cpp::behaviortree_cpp ${geometry_msgs_TARGETS} @@ -282,7 +285,7 @@ target_link_libraries(generate_nav2_tree_nodes_xml PRIVATE nav2_util::nav2_util_core ) # allow generate_nav2_tree_nodes_xml to find plugins_list.hpp -target_include_directories(generate_nav2_tree_nodes_xml PRIVATE ${GENERATED_DIR}) +target_include_directories(generate_nav2_tree_nodes_xml PRIVATE ${GENERATED_DIR} "$") install(TARGETS generate_nav2_tree_nodes_xml DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY include/ @@ -328,6 +331,7 @@ ament_export_dependencies( std_srvs tf2 tf2_ros + nav2_ros_common ) ament_export_targets(${library_name}) diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp index db5f938a9fe..96fb5df0dce 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp @@ -25,7 +25,7 @@ #include "behaviortree_cpp/loggers/groot2_publisher.h" #include "behaviortree_cpp/xml_parsing.h" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { @@ -49,7 +49,7 @@ class BehaviorTreeEngine */ explicit BehaviorTreeEngine( const std::vector & plugin_libraries, - rclcpp::Node::SharedPtr node); + nav2::LifecycleNode::SharedPtr node); virtual ~BehaviorTreeEngine() {} /** diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp index 58c1f422b5a..682dc7a9a09 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp @@ -21,7 +21,7 @@ #include "behaviortree_cpp/action_node.h" #include "behaviortree_cpp/json_export.h" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/json_utils.hpp" @@ -53,7 +53,7 @@ class BtActionNode : public BT::ActionNodeBase const BT::NodeConfiguration & conf) : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name), should_send_goal_(true) { - node_ = config().blackboard->template get("node"); + node_ = config().blackboard->template get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); @@ -96,7 +96,7 @@ class BtActionNode : public BT::ActionNodeBase void createActionClient(const std::string & action_name) { // Now that we have the ROS node to use, create the action client for this BT action - action_client_ = rclcpp_action::create_client(node_, action_name, callback_group_); + action_client_ = node_->create_action_client(action_name, callback_group_); // Make sure the server is actually there before continuing RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str()); @@ -382,7 +382,7 @@ class BtActionNode : public BT::ActionNodeBase void send_new_goal() { goal_result_available_ = false; - auto send_goal_options = typename rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = typename nav2::ActionClient::SendGoalOptions(); send_goal_options.result_callback = [this](const typename rclcpp_action::ClientGoalHandle::WrappedResult & result) { if (future_goal_handle_) { @@ -465,7 +465,7 @@ class BtActionNode : public BT::ActionNodeBase } std::string action_name_; - typename std::shared_ptr> action_client_; + typename nav2::ActionClient::SharedPtr action_client_; // All ROS2 actions have a goal and a result typename ActionT::Goal goal_; @@ -478,7 +478,7 @@ class BtActionNode : public BT::ActionNodeBase std::shared_ptr feedback_; // The node that will be used for any ROS operations - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp index 24e96d871b0..d5d1fa4c3a4 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp @@ -24,10 +24,8 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_behavior_tree/behavior_tree_engine.hpp" #include "nav2_behavior_tree/ros_topic_logger.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/simple_action_server.hpp" -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/simple_action_server.hpp" namespace nav2_behavior_tree { @@ -35,11 +33,11 @@ namespace nav2_behavior_tree * @class nav2_behavior_tree::BtActionServer * @brief An action server that uses behavior tree to execute an action */ -template +template class BtActionServer { public: - using ActionServer = nav2_util::SimpleActionServer; + using ActionServer = nav2::SimpleActionServer; typedef std::function OnGoalReceivedCallback; typedef std::function OnLoopCallback; @@ -51,7 +49,7 @@ class BtActionServer * @brief A constructor for nav2_behavior_tree::BtActionServer class */ explicit BtActionServer( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const typename NodeT::WeakPtr & parent, const std::string & action_name, const std::vector & plugin_lib_names, const std::string & default_bt_xml_filename, @@ -236,7 +234,7 @@ class BtActionServer std::string action_name_; // Our action server implements the template action - std::shared_ptr action_server_; + typename ActionServer::SharedPtr action_server_; // Behavior Tree to be executed when goal is received BT::Tree tree_; @@ -258,10 +256,10 @@ class BtActionServer std::vector error_code_name_prefixes_; // A regular, non-spinning ROS node that we can use for calls to the action client - rclcpp::Node::SharedPtr client_node_; + nav2::LifecycleNode::SharedPtr client_node_; // Parent node - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + typename NodeT::WeakPtr node_; // Clock rclcpp::Clock::SharedPtr clock_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp index 61271650b3c..17e4f66bcba 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp @@ -26,16 +26,16 @@ #include "nav2_msgs/action/navigate_to_pose.hpp" #include "nav2_behavior_tree/bt_action_server.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "rcl_action/action_server.h" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { -template -BtActionServer::BtActionServer( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, +template +BtActionServer::BtActionServer( + const typename NodeT::WeakPtr & parent, const std::string & action_name, const std::vector & plugin_lib_names, const std::string & default_bt_xml_filename, @@ -121,12 +121,12 @@ BtActionServer::BtActionServer( } } -template -BtActionServer::~BtActionServer() +template +BtActionServer::~BtActionServer() {} -template -bool BtActionServer::on_configure() +template +bool BtActionServer::on_configure() { auto node = node_.lock(); if (!node) { @@ -148,25 +148,25 @@ bool BtActionServer::on_configure() "--"}); // Support for handling the topic-based goal pose from rviz - client_node_ = std::make_shared("_", options); + client_node_ = std::make_shared("_", options); + client_node_->configure(); + client_node_->activate(); // Declare parameters for common client node applications to share with BT nodes // Declare if not declared in case being used an external application, then copying // all of the main node's parameters to the client for BT nodes to obtain - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "global_frame", rclcpp::ParameterValue(std::string("map"))); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link"))); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "transform_tolerance", rclcpp::ParameterValue(0.1)); rclcpp::copy_all_parameter_values(node, client_node_); - action_server_ = std::make_shared( - node->get_node_base_interface(), - node->get_node_clock_interface(), - node->get_node_logging_interface(), - node->get_node_waitables_interface(), - action_name_, std::bind(&BtActionServer::executeCallback, this), + // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the subscription + // to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode + action_server_ = nav2::interfaces::create_action_server( + node, action_name_, std::bind(&BtActionServer::executeCallback, this), nullptr, std::chrono::milliseconds(500), false); // Get parameters for BT timeouts @@ -191,7 +191,7 @@ bool BtActionServer::on_configure() blackboard_ = BT::Blackboard::create(); // Put items on the blackboard - blackboard_->set("node", client_node_); // NOLINT + blackboard_->set("node", client_node_); // NOLINT blackboard_->set("server_timeout", default_server_timeout_); // NOLINT blackboard_->set("bt_loop_duration", bt_loop_duration_); // NOLINT blackboard_->set( @@ -201,8 +201,8 @@ bool BtActionServer::on_configure() return true; } -template -bool BtActionServer::on_activate() +template +bool BtActionServer::on_activate() { resetInternalError(); if (!loadBehaviorTree(default_bt_xml_filename_)) { @@ -213,16 +213,18 @@ bool BtActionServer::on_activate() return true; } -template -bool BtActionServer::on_deactivate() +template +bool BtActionServer::on_deactivate() { action_server_->deactivate(); return true; } -template -bool BtActionServer::on_cleanup() +template +bool BtActionServer::on_cleanup() { + client_node_->deactivate(); + client_node_->cleanup(); client_node_.reset(); action_server_.reset(); topic_logger_.reset(); @@ -235,15 +237,17 @@ bool BtActionServer::on_cleanup() return true; } -template -void BtActionServer::setGrootMonitoring(const bool enable, const unsigned server_port) +template +void BtActionServer::setGrootMonitoring( + const bool enable, + const unsigned server_port) { enable_groot_monitoring_ = enable; groot_server_port_ = server_port; } -template -bool BtActionServer::loadBehaviorTree(const std::string & bt_xml_filename) +template +bool BtActionServer::loadBehaviorTree(const std::string & bt_xml_filename) { // Empty filename is default for backward compatibility auto filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename; @@ -299,8 +303,8 @@ bool BtActionServer::loadBehaviorTree(const std::string & bt_xml_filena return true; } -template -void BtActionServer::executeCallback() +template +void BtActionServer::executeCallback() { if (!on_goal_received_callback_(action_server_->get_current_goal())) { // Give server an opportunity to populate the result message @@ -368,8 +372,10 @@ void BtActionServer::executeCallback() cleanErrorCodes(); } -template -void BtActionServer::setInternalError(uint16_t error_code, const std::string & error_msg) +template +void BtActionServer::setInternalError( + uint16_t error_code, + const std::string & error_msg) { internal_error_code_ = error_code; internal_error_msg_ = error_msg; @@ -377,15 +383,15 @@ void BtActionServer::setInternalError(uint16_t error_code, const std::s internal_error_code_, internal_error_msg_.c_str()); } -template -void BtActionServer::resetInternalError(void) +template +void BtActionServer::resetInternalError(void) { internal_error_code_ = ActionT::Result::NONE; internal_error_msg_ = ""; } -template -bool BtActionServer::populateInternalError( +template +bool BtActionServer::populateInternalError( typename std::shared_ptr result) { if (internal_error_code_ != ActionT::Result::NONE) { @@ -396,8 +402,8 @@ bool BtActionServer::populateInternalError( return false; } -template -void BtActionServer::populateErrorCode( +template +void BtActionServer::populateErrorCode( typename std::shared_ptr result) { int highest_priority_error_code = std::numeric_limits::max(); @@ -432,8 +438,8 @@ void BtActionServer::populateErrorCode( } } -template -void BtActionServer::cleanErrorCodes() +template +void BtActionServer::cleanErrorCodes() { std::string name; for (const auto & error_code_name_prefix : error_code_name_prefixes_) { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp index d63dc1e104e..ed8ff730071 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp @@ -20,7 +20,7 @@ #include #include "behaviortree_cpp/action_node.h" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "nav2_behavior_tree/bt_utils.hpp" @@ -49,7 +49,7 @@ class BtCancelActionNode : public BT::ActionNodeBase const BT::NodeConfiguration & conf) : BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name) { - node_ = config().blackboard->template get("node"); + node_ = config().blackboard->template get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); @@ -85,7 +85,7 @@ class BtCancelActionNode : public BT::ActionNodeBase void createActionClient(const std::string & action_name) { // Now that we have the ROS node to use, create the action client for this BT action - action_client_ = rclcpp_action::create_client(node_, action_name, callback_group_); + action_client_ = node_->create_action_client(action_name, callback_group_); // Make sure the server is actually there before continuing RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str()); @@ -158,10 +158,10 @@ class BtCancelActionNode : public BT::ActionNodeBase protected: std::string action_name_; - typename std::shared_ptr> action_client_; + typename nav2::ActionClient::SharedPtr action_client_; // The node that will be used for any ROS operations - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp index 6f55e1a127e..80b2d8cbb9b 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp @@ -21,11 +21,11 @@ #include "behaviortree_cpp/action_node.h" #include "behaviortree_cpp/json_export.h" -#include "nav2_util/node_utils.hpp" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/json_utils.hpp" -#include "nav2_util/service_client.hpp" +#include "nav2_ros_common/service_client.hpp" namespace nav2_behavior_tree { @@ -113,9 +113,10 @@ class BtServiceNode : public BT::ActionNodeBase getInput("service_name", service_new); if (service_new != service_name_ || !service_client_) { service_name_ = service_new; - node_ = config().blackboard->template get("node"); - service_client_ = std::make_shared>( - service_name_, node_, true /*creates and spins an internal executor*/); + node_ = config().blackboard->template get("node"); + service_client_ = + node_->create_client( + service_name_, true /*creates and spins an internal executor*/); } } @@ -262,11 +263,11 @@ class BtServiceNode : public BT::ActionNodeBase } std::string service_name_, service_node_name_; - typename nav2_util::ServiceClient::SharedPtr service_client_; + typename nav2::ServiceClient::SharedPtr service_client_; std::shared_ptr request_; // The node that will be used for any ROS operations - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; // The timeout value while to use in the tick loop while waiting for // a result from the server diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp index ace8f07b527..e48da89094a 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/bt_utils.hpp @@ -19,8 +19,7 @@ #include #include -#include "rclcpp/time.hpp" -#include "rclcpp/node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/behavior_tree.h" #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" @@ -342,14 +341,14 @@ inline std::chrono::milliseconds convertFromString(co /** * @brief Return parameter value from behavior tree node or ros2 parameter file. - * @param node rclcpp::Node::SharedPtr + * @param node nav2::LifecycleNode::SharedPtr * @param param_name std::string * @param behavior_tree_node T2 * @return */ template T1 deconflictPortAndParamFrame( - rclcpp::Node::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::string param_name, const T2 * behavior_tree_node) { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/append_goal_pose_to_goals_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/append_goal_pose_to_goals_action.hpp index 41c4b5a1ef2..3df8ac829bd 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/append_goal_pose_to_goals_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/append_goal_pose_to_goals_action.hpp @@ -25,6 +25,7 @@ #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "behaviortree_cpp/action_node.h" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp index f4a740abc84..cd6d98789b8 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_action.hpp @@ -20,6 +20,7 @@ #include "nav2_behavior_tree/bt_action_node.hpp" #include "nav2_msgs/action/assisted_teleop.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_cancel_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_cancel_node.hpp index 55fe337fe8e..be924bfc44e 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_cancel_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/assisted_teleop_cancel_node.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/assisted_teleop.hpp" #include "nav2_behavior_tree/bt_cancel_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp index c608ff1c946..144e8858ae5 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_action.hpp @@ -19,6 +19,7 @@ #include "nav2_behavior_tree/bt_action_node.hpp" #include "nav2_msgs/action/back_up.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_cancel_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_cancel_node.hpp index d59bbff5a57..04262ef9d15 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_cancel_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/back_up_cancel_node.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/back_up.hpp" #include "nav2_behavior_tree/bt_cancel_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/clear_costmap_service.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/clear_costmap_service.hpp index 3b3e00b2ca4..2d4afc27cf0 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/clear_costmap_service.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/clear_costmap_service.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/srv/clear_entire_costmap.hpp" #include "nav2_msgs/srv/clear_costmap_around_robot.hpp" #include "nav2_msgs/srv/clear_costmap_except_region.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_action.hpp index 6d258552a7f..ac155a8f06b 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_action.hpp @@ -20,6 +20,7 @@ #include "nav2_msgs/action/compute_and_track_route.hpp" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_cancel_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_cancel_node.hpp index a7d79d7a5a8..8cc28b9e567 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_cancel_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_and_track_route_cancel_node.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/compute_and_track_route.hpp" #include "nav2_behavior_tree/bt_cancel_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp index 4e3cc400ff0..48a4e407d1b 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_through_poses_action.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/compute_path_through_poses.hpp" #include "nav_msgs/msg/path.h" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp index 157b27cea88..626dd2cf591 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_path_to_pose_action.hpp @@ -20,6 +20,7 @@ #include "nav2_msgs/action/compute_path_to_pose.hpp" #include "nav_msgs/msg/path.h" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_route_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_route_action.hpp index ac810381d42..c54d0f73b83 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_route_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/compute_route_action.hpp @@ -20,6 +20,7 @@ #include "nav2_msgs/action/compute_route.hpp" #include "nav_msgs/msg/path.h" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/concatenate_paths_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/concatenate_paths_action.hpp index adfc121af00..db7de08fd30 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/concatenate_paths_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/concatenate_paths_action.hpp @@ -22,6 +22,7 @@ #include "nav_msgs/msg/path.hpp" #include "behaviortree_cpp/action_node.h" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_cancel_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_cancel_node.hpp index a9c742df319..d7a51b19356 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_cancel_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_cancel_node.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/follow_path.hpp" #include "nav2_behavior_tree/bt_cancel_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_selector_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_selector_node.hpp index 44ac5ce40c0..ebc29fa9721 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_selector_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/controller_selector_node.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp/action_node.h" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { @@ -93,11 +93,11 @@ class ControllerSelector : public BT::SyncActionNode */ void callbackControllerSelect(const std_msgs::msg::String::SharedPtr msg); - rclcpp::Subscription::SharedPtr controller_selector_sub_; + nav2::Subscription::SharedPtr controller_selector_sub_; std::string last_selected_controller_; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp index 2a2ac3948ca..274d1f538f8 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_action.hpp @@ -19,6 +19,7 @@ #include "nav2_behavior_tree/bt_action_node.hpp" #include "nav2_msgs/action/drive_on_heading.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_cancel_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_cancel_node.hpp index a2f13a94fef..1988cdfefa8 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_cancel_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/drive_on_heading_cancel_node.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/drive_on_heading.hpp" #include "nav2_behavior_tree/bt_cancel_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/extract_route_nodes_as_goals_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/extract_route_nodes_as_goals_action.hpp index 57cc9e72f4a..9da4f407320 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/extract_route_nodes_as_goals_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/extract_route_nodes_as_goals_action.hpp @@ -25,6 +25,7 @@ #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "behaviortree_cpp/action_node.h" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/follow_path_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/follow_path_action.hpp index 80e24e4f0fa..1dc46f19e9f 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/follow_path_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/follow_path_action.hpp @@ -20,6 +20,7 @@ #include "nav2_msgs/action/follow_path.hpp" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_current_pose_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_current_pose_action.hpp index 118edd28524..b6385a2f7ba 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_current_pose_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_current_pose_action.hpp @@ -24,6 +24,7 @@ #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_behavior_tree/bt_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/action_node.h" diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_next_few_goals_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_next_few_goals_action.hpp index 83534b34f2b..f4dc7d6a13a 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_next_few_goals_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_next_few_goals_action.hpp @@ -25,6 +25,7 @@ #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "behaviortree_cpp/action_node.h" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp index fa336182064..d757f5665c9 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/get_pose_from_path_action.hpp @@ -27,7 +27,7 @@ #include "nav2_behavior_tree/json_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" - +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/goal_checker_selector_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/goal_checker_selector_node.hpp index 16ae0b96596..820a1a7f71f 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/goal_checker_selector_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/goal_checker_selector_node.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp/action_node.h" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { @@ -93,11 +93,13 @@ class GoalCheckerSelector : public BT::SyncActionNode */ void callbackGoalCheckerSelect(const std_msgs::msg::String::SharedPtr msg); - rclcpp::Subscription::SharedPtr goal_checker_selector_sub_; + nav2::Subscription::SharedPtr goal_checker_selector_sub_; std::string last_selected_goal_checker_; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; + rclcpp::CallbackGroup::SharedPtr callback_group_; + rclcpp::executors::SingleThreadedExecutor callback_group_executor_; std::string topic_name_; }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp index 71c6597683f..43f39f4cc46 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp @@ -21,6 +21,7 @@ #include "nav_msgs/msg/goals.hpp" #include "nav2_msgs/action/navigate_through_poses.hpp" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_to_pose_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_to_pose_action.hpp index 770bfee0ff8..26e5823ae99 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_to_pose_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_to_pose_action.hpp @@ -21,6 +21,7 @@ #include "geometry_msgs/msg/quaternion.hpp" #include "nav2_msgs/action/navigate_to_pose.hpp" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/planner_selector_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/planner_selector_node.hpp index 173b2cf7b92..07026ac64f9 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/planner_selector_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/planner_selector_node.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp/action_node.h" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { @@ -94,11 +94,11 @@ class PlannerSelector : public BT::SyncActionNode void callbackPlannerSelect(const std_msgs::msg::String::SharedPtr msg); - rclcpp::Subscription::SharedPtr planner_selector_sub_; + nav2::Subscription::SharedPtr planner_selector_sub_; std::string last_selected_planner_; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/progress_checker_selector_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/progress_checker_selector_node.hpp index 2b910404ba3..c58f615dbf7 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/progress_checker_selector_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/progress_checker_selector_node.hpp @@ -22,7 +22,7 @@ #include "behaviortree_cpp/action_node.h" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { @@ -92,11 +92,13 @@ class ProgressCheckerSelector : public BT::SyncActionNode */ void callbackProgressCheckerSelect(const std_msgs::msg::String::SharedPtr msg); - rclcpp::Subscription::SharedPtr progress_checker_selector_sub_; + nav2::Subscription::SharedPtr progress_checker_selector_sub_; std::string last_selected_progress_checker_; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; + rclcpp::CallbackGroup::SharedPtr callback_group_; + rclcpp::executors::SingleThreadedExecutor callback_group_executor_; std::string topic_name_; }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/reinitialize_global_localization_service.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/reinitialize_global_localization_service.hpp index cf358cb937c..b5f60e54fd5 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/reinitialize_global_localization_service.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/reinitialize_global_localization_service.hpp @@ -19,6 +19,7 @@ #include "nav2_behavior_tree/bt_service_node.hpp" #include "std_srvs/srv/empty.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp index db5f313249f..a76394e2ffe 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_in_collision_goals_action.hpp @@ -19,7 +19,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav_msgs/msg/goals.hpp" #include "nav2_behavior_tree/bt_service_node.hpp" #include "nav2_msgs/srv/get_costs.hpp" diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp index 61ee3907f3e..a651318379f 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/remove_passed_goals_action.hpp @@ -27,7 +27,7 @@ #include "nav2_msgs/msg/waypoint_status.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_util/robot_utils.hpp" - +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { @@ -75,7 +75,7 @@ class RemovePassedGoals : public BT::ActionNodeBase double viapoint_achieved_radius_; double transform_tolerance_; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_; std::string robot_base_frame_; }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smooth_path_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smooth_path_action.hpp index 26a9092df3f..d49e99077f0 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smooth_path_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smooth_path_action.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/smooth_path.hpp" #include "nav_msgs/msg/path.h" #include "nav2_behavior_tree/bt_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smoother_selector_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smoother_selector_node.hpp index 2dd743d1af5..f752fafb913 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smoother_selector_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/smoother_selector_node.hpp @@ -23,7 +23,7 @@ #include "behaviortree_cpp/action_node.h" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { @@ -93,11 +93,11 @@ class SmootherSelector : public BT::SyncActionNode */ void callbackSmootherSelect(const std_msgs::msg::String::SharedPtr msg); - rclcpp::Subscription::SharedPtr smoother_selector_sub_; + nav2::Subscription::SharedPtr smoother_selector_sub_; std::string last_selected_smoother_; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp index e66de027c28..431e845cc23 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_action.hpp @@ -19,6 +19,7 @@ #include "nav2_behavior_tree/bt_action_node.hpp" #include "nav2_msgs/action/spin.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_cancel_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_cancel_node.hpp index 0e747fa70d0..4f53d970c94 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_cancel_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/spin_cancel_node.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/spin.hpp" #include "nav2_behavior_tree/bt_cancel_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_action.hpp index 25009266f42..310c72783d1 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_action.hpp @@ -24,6 +24,7 @@ #include "nav_msgs/msg/path.hpp" #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/json_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp index c8affd1ccf5..6ce8a76fd64 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/truncate_path_local_action.hpp @@ -26,6 +26,7 @@ #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/json_utils.hpp" #include "tf2_ros/buffer.h" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_action.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_action.hpp index 866dc130901..11c2acade32 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_action.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_action.hpp @@ -19,6 +19,7 @@ #include "nav2_behavior_tree/bt_action_node.hpp" #include "nav2_msgs/action/wait.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_cancel_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_cancel_node.hpp index 1545e9da2e5..07a748f5de6 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_cancel_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/wait_cancel_node.hpp @@ -21,6 +21,7 @@ #include "nav2_msgs/action/wait.hpp" #include "nav2_behavior_tree/bt_cancel_action_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_behavior_tree { diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp index 67833a383b3..847253321db 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp @@ -20,7 +20,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" namespace nav2_behavior_tree diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp index bcd170340d3..db615c06181 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp @@ -18,7 +18,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "tf2_ros/buffer.h" #include "nav2_behavior_tree/bt_utils.hpp" @@ -79,7 +79,7 @@ class ArePosesNearCondition : public BT::ConditionNode } private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_; double transform_tolerance_; std::string global_frame_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp index e0837126b1f..abcf722b872 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/distance_traveled_condition.hpp @@ -21,7 +21,7 @@ #include "behaviortree_cpp/condition_node.h" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "tf2_ros/buffer.h" #include "nav2_behavior_tree/bt_utils.hpp" @@ -74,7 +74,7 @@ class DistanceTraveledCondition : public BT::ConditionNode } private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_; geometry_msgs::msg::PoseStamped start_pose_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp index 7d71bd097bd..4eb76480f54 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.hpp @@ -18,8 +18,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" - +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "behaviortree_cpp/json_export.h" #include "nav_msgs/msg/goals.hpp" @@ -74,7 +73,7 @@ class GloballyUpdatedGoalCondition : public BT::ConditionNode private: bool first_time; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; geometry_msgs::msg::PoseStamped goal_; nav_msgs::msg::Goals goals_; }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp index fa4b26e33e6..aeebfcb3634 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp @@ -18,7 +18,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "behaviortree_cpp/json_export.h" #include "nav2_behavior_tree/bt_utils.hpp" @@ -94,7 +94,7 @@ class GoalReachedCondition : public BT::ConditionNode {} private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_; double goal_reached_tol_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp index 41702b48751..2c95e1e880e 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.hpp @@ -19,7 +19,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "sensor_msgs/msg/battery_state.hpp" #include "behaviortree_cpp/condition_node.h" @@ -82,7 +82,7 @@ class IsBatteryChargingCondition : public BT::ConditionNode rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; - rclcpp::Subscription::SharedPtr battery_sub_; + nav2::Subscription::SharedPtr battery_sub_; std::string battery_topic_; bool is_battery_charging_; }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp index 17ac78b2edc..d66eb5eea72 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_battery_low_condition.hpp @@ -20,7 +20,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "sensor_msgs/msg/battery_state.hpp" #include "behaviortree_cpp/condition_node.h" @@ -85,10 +85,10 @@ class IsBatteryLowCondition : public BT::ConditionNode */ void batteryCallback(sensor_msgs::msg::BatteryState::SharedPtr msg); - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; - rclcpp::Subscription::SharedPtr battery_sub_; + nav2::Subscription::SharedPtr battery_sub_; std::string battery_topic_; double min_battery_; bool is_voltage_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_path_valid_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_path_valid_condition.hpp index c70e2f53010..334eaefd6f0 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_path_valid_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_path_valid_condition.hpp @@ -18,12 +18,12 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "behaviortree_cpp/json_export.h" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_msgs/srv/is_path_valid.hpp" -#include "nav2_util/service_client.hpp" +#include "nav2_ros_common/service_client.hpp" #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/json_utils.hpp" @@ -81,8 +81,8 @@ class IsPathValidCondition : public BT::ConditionNode } private: - rclcpp::Node::SharedPtr node_; - nav2_util::ServiceClient::SharedPtr client_; + nav2::LifecycleNode::SharedPtr node_; + nav2::ServiceClient::SharedPtr client_; // The timeout value while waiting for a response from the // is path valid service std::chrono::milliseconds server_timeout_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stopped_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stopped_condition.hpp index f8a93e0e703..2d1bbe31449 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stopped_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stopped_condition.hpp @@ -18,7 +18,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "behaviortree_cpp/json_export.h" #include "nav_msgs/msg/odometry.hpp" @@ -79,7 +79,7 @@ class IsStoppedCondition : public BT::ConditionNode } private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; double velocity_threshold_; std::chrono::milliseconds duration_stopped_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp index 24229fb85f1..64dccaca944 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/is_stuck_condition.hpp @@ -19,7 +19,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "nav_msgs/msg/odometry.hpp" @@ -85,7 +85,7 @@ class IsStuckCondition : public BT::ConditionNode private: // The node that will be used for any ROS operations - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; std::thread callback_group_executor_thread; @@ -93,7 +93,7 @@ class IsStuckCondition : public BT::ConditionNode std::atomic is_stuck_; // Listen to odometry - rclcpp::Subscription::SharedPtr odom_sub_; + nav2::Subscription::SharedPtr odom_sub_; // Store history of odometry measurements std::deque odom_history_; std::deque::size_type odom_history_size_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.hpp index 0460cdf3080..66b2cd5d468 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.hpp @@ -17,7 +17,7 @@ #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "behaviortree_cpp/json_export.h" #include "nav_msgs/msg/path.hpp" @@ -67,7 +67,7 @@ class PathExpiringTimerCondition : public BT::ConditionNode } private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::Time start_; nav_msgs::msg::Path prev_path_; double period_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/time_expired_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/time_expired_condition.hpp index 0ea482ab4f2..a3631191e04 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/time_expired_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/time_expired_condition.hpp @@ -18,7 +18,7 @@ #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" namespace nav2_behavior_tree @@ -67,7 +67,7 @@ class TimeExpiredCondition : public BT::ConditionNode } private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::Time start_; double period_; }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp index 13d61a74a6e..41a86ee813d 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/transform_available_condition.hpp @@ -19,7 +19,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "behaviortree_cpp/condition_node.h" #include "tf2_ros/buffer.h" @@ -75,7 +75,7 @@ class TransformAvailableCondition : public BT::ConditionNode } private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_; std::atomic was_found_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp index e649fd75984..64e4a7c4a75 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/distance_controller.hpp @@ -66,7 +66,7 @@ class DistanceController : public BT::DecoratorNode */ BT::NodeStatus tick() override; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_; double transform_tolerance_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp index 224f472d146..2c6d69895e6 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/goal_updater_node.hpp @@ -97,15 +97,15 @@ class GoalUpdater : public BT::DecoratorNode */ void callback_updated_goals(const nav_msgs::msg::Goals::SharedPtr msg); - rclcpp::Subscription::SharedPtr goal_sub_; - rclcpp::Subscription::SharedPtr goals_sub_; + nav2::Subscription::SharedPtr goal_sub_; + nav2::Subscription::SharedPtr goals_sub_; geometry_msgs::msg::PoseStamped last_goal_received_; bool last_goal_received_set_{false}; nav_msgs::msg::Goals last_goals_received_; bool last_goals_received_set_{false}; - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; std::string goal_updater_topic_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.hpp index a679cf6dc76..b147b7e665c 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.hpp @@ -110,7 +110,7 @@ class PathLongerOnApproach : public BT::DecoratorNode nav_msgs::msg::Path old_path_; double prox_len_ = std::numeric_limits::max(); double length_factor_ = std::numeric_limits::max(); - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; bool first_time_ = true; }; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp index 3afc019af5b..6d2fd851b33 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/plugins/decorator/speed_controller.hpp @@ -103,7 +103,7 @@ class SpeedController : public BT::DecoratorNode period_ = 1.0 / rate; } - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; // To keep track of time to reset rclcpp::Time start_; diff --git a/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp b/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp index a65334e5b61..e418c5846ad 100644 --- a/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp +++ b/nav2_behavior_tree/include/nav2_behavior_tree/ros_topic_logger.hpp @@ -37,18 +37,17 @@ class RosTopicLogger : public BT::StatusChangeLogger public: /** * @brief A constructor for nav2_behavior_tree::RosTopicLogger - * @param ros_node Weak pointer to parent rclcpp::Node + * @param ros_node Weak pointer to parent nav2::LifecycleNode * @param tree BT to monitor */ - RosTopicLogger(const rclcpp::Node::WeakPtr & ros_node, const BT::Tree & tree) + RosTopicLogger(const nav2::LifecycleNode::WeakPtr & ros_node, const BT::Tree & tree) : StatusChangeLogger(tree.rootNode()) { auto node = ros_node.lock(); clock_ = node->get_clock(); logger_ = node->get_logger(); log_pub_ = node->create_publisher( - "behavior_tree_log", - rclcpp::QoS(10)); + "behavior_tree_log"); } /** diff --git a/nav2_behavior_tree/package.xml b/nav2_behavior_tree/package.xml index 31da48c1868..e931df421e2 100644 --- a/nav2_behavior_tree/package.xml +++ b/nav2_behavior_tree/package.xml @@ -26,6 +26,7 @@ std_srvs tf2 tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_behavior_tree/plugins/action/concatenate_paths_action.cpp b/nav2_behavior_tree/plugins/action/concatenate_paths_action.cpp index 4ebc4df5e4c..4fd13db40dc 100644 --- a/nav2_behavior_tree/plugins/action/concatenate_paths_action.cpp +++ b/nav2_behavior_tree/plugins/action/concatenate_paths_action.cpp @@ -43,7 +43,7 @@ inline BT::NodeStatus ConcatenatePaths::tick() if (input_path1.poses.empty() && input_path2.poses.empty()) { RCLCPP_ERROR( - config().blackboard->get("node")->get_logger(), + config().blackboard->get("node")->get_logger(), "No input paths provided to concatenate. Both paths are empty."); return BT::NodeStatus::FAILURE; } diff --git a/nav2_behavior_tree/plugins/action/controller_selector_node.cpp b/nav2_behavior_tree/plugins/action/controller_selector_node.cpp index f1730870b4b..860f1ed12de 100644 --- a/nav2_behavior_tree/plugins/action/controller_selector_node.cpp +++ b/nav2_behavior_tree/plugins/action/controller_selector_node.cpp @@ -49,23 +49,17 @@ void ControllerSelector::createROSInterfaces() getInput("topic_name", topic_new); if (topic_new != topic_name_ || !controller_selector_sub_) { topic_name_ = topic_new; - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); - - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); - - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; controller_selector_sub_ = node_->create_subscription( topic_name_, - qos, std::bind(&ControllerSelector::callbackControllerSelect, this, _1), - sub_option); + nav2::qos::LatchedSubscriptionQoS(), + callback_group_); } } diff --git a/nav2_behavior_tree/plugins/action/get_current_pose_action.cpp b/nav2_behavior_tree/plugins/action/get_current_pose_action.cpp index b6cc003d3b8..d491ade4ccf 100644 --- a/nav2_behavior_tree/plugins/action/get_current_pose_action.cpp +++ b/nav2_behavior_tree/plugins/action/get_current_pose_action.cpp @@ -32,7 +32,7 @@ GetCurrentPoseAction::GetCurrentPoseAction( const BT::NodeConfiguration & conf) : BT::ActionNodeBase(name, conf) { - auto node = config().blackboard->get("node"); + auto node = config().blackboard->get("node"); tf_ = config().blackboard->get>("tf_buffer"); node->get_parameter("transform_tolerance", transform_tolerance_); global_frame_ = BT::deconflictPortAndParamFrame( @@ -50,7 +50,7 @@ inline BT::NodeStatus GetCurrentPoseAction::tick() current_pose, *tf_, global_frame_, robot_base_frame_, transform_tolerance_)) { RCLCPP_WARN( - config().blackboard->get("node")->get_logger(), + config().blackboard->get("node")->get_logger(), "Current robot pose is not available."); return BT::NodeStatus::FAILURE; } diff --git a/nav2_behavior_tree/plugins/action/goal_checker_selector_node.cpp b/nav2_behavior_tree/plugins/action/goal_checker_selector_node.cpp index 3616b87de45..20df1bcca9c 100644 --- a/nav2_behavior_tree/plugins/action/goal_checker_selector_node.cpp +++ b/nav2_behavior_tree/plugins/action/goal_checker_selector_node.cpp @@ -46,13 +46,17 @@ void GoalCheckerSelector::createROSInterfaces() getInput("topic_name", topic_new); if (topic_new != topic_name_ || !goal_checker_selector_sub_) { topic_name_ = topic_new; - node_ = config().blackboard->get("node"); - - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + node_ = config().blackboard->get("node"); + callback_group_ = node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, + false); + callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); goal_checker_selector_sub_ = node_->create_subscription( - topic_name_, qos, std::bind(&GoalCheckerSelector::callbackGoalCheckerSelect, this, _1)); + topic_name_, + std::bind(&GoalCheckerSelector::callbackGoalCheckerSelect, this, _1), + nav2::qos::LatchedSubscriptionQoS(), + callback_group_); } } @@ -62,7 +66,7 @@ BT::NodeStatus GoalCheckerSelector::tick() initialize(); } - rclcpp::spin_some(node_); + callback_group_executor_.spin_some(); // This behavior always use the last selected goal checker received from the topic input. // When no input is specified it uses the default goal checker. diff --git a/nav2_behavior_tree/plugins/action/planner_selector_node.cpp b/nav2_behavior_tree/plugins/action/planner_selector_node.cpp index 4e9c1d1587d..6dd1806d67a 100644 --- a/nav2_behavior_tree/plugins/action/planner_selector_node.cpp +++ b/nav2_behavior_tree/plugins/action/planner_selector_node.cpp @@ -49,22 +49,17 @@ void PlannerSelector::createROSInterfaces() getInput("topic_name", topic_new); if (topic_new != topic_name_ || !planner_selector_sub_) { topic_name_ = topic_new; - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); - - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; planner_selector_sub_ = node_->create_subscription( topic_name_, - qos, std::bind(&PlannerSelector::callbackPlannerSelect, this, _1), - sub_option); + nav2::qos::LatchedSubscriptionQoS(), + callback_group_); } } diff --git a/nav2_behavior_tree/plugins/action/progress_checker_selector_node.cpp b/nav2_behavior_tree/plugins/action/progress_checker_selector_node.cpp index 3f4ea97c2d9..71d0b308e2a 100644 --- a/nav2_behavior_tree/plugins/action/progress_checker_selector_node.cpp +++ b/nav2_behavior_tree/plugins/action/progress_checker_selector_node.cpp @@ -45,14 +45,17 @@ void ProgressCheckerSelector::createROSInterfaces() getInput("topic_name", topic_new); if (topic_new != topic_name_ || !progress_checker_selector_sub_) { topic_name_ = topic_new; - node_ = config().blackboard->get("node"); - - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + node_ = config().blackboard->get("node"); + callback_group_ = node_->create_callback_group( + rclcpp::CallbackGroupType::MutuallyExclusive, + false); + callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); progress_checker_selector_sub_ = node_->create_subscription( - topic_name_, qos, - std::bind(&ProgressCheckerSelector::callbackProgressCheckerSelect, this, _1)); + topic_name_, + std::bind(&ProgressCheckerSelector::callbackProgressCheckerSelect, this, _1), + nav2::qos::LatchedSubscriptionQoS(), + callback_group_); } } @@ -62,7 +65,7 @@ BT::NodeStatus ProgressCheckerSelector::tick() initialize(); } - rclcpp::spin_some(node_); + callback_group_executor_.spin_some(); // This behavior always use the last selected progress checker received from the topic input. // When no input is specified it uses the default goaprogressl checker. diff --git a/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp b/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp index 53dd6db6e78..335d5e60c37 100644 --- a/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp +++ b/nav2_behavior_tree/plugins/action/remove_passed_goals_action.cpp @@ -36,7 +36,7 @@ void RemovePassedGoals::initialize() getInput("radius", viapoint_achieved_radius_); tf_ = config().blackboard->get>("tf_buffer"); - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); node_->get_parameter("transform_tolerance", transform_tolerance_); robot_base_frame_ = BT::deconflictPortAndParamFrame( diff --git a/nav2_behavior_tree/plugins/action/smoother_selector_node.cpp b/nav2_behavior_tree/plugins/action/smoother_selector_node.cpp index 58dad4866db..1e7768e7020 100644 --- a/nav2_behavior_tree/plugins/action/smoother_selector_node.cpp +++ b/nav2_behavior_tree/plugins/action/smoother_selector_node.cpp @@ -50,22 +50,17 @@ void SmootherSelector::createROSInterfaces() getInput("topic_name", topic_new); if (topic_new != topic_name_ || !smoother_selector_sub_) { topic_name_ = topic_new; - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); - - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; smoother_selector_sub_ = node_->create_subscription( topic_name_, - qos, std::bind(&SmootherSelector::callbackSmootherSelect, this, _1), - sub_option); + nav2::qos::LatchedSubscriptionQoS(), + callback_group_); } } diff --git a/nav2_behavior_tree/plugins/action/truncate_path_action.cpp b/nav2_behavior_tree/plugins/action/truncate_path_action.cpp index 7bebfbfba38..6d985f42d54 100644 --- a/nav2_behavior_tree/plugins/action/truncate_path_action.cpp +++ b/nav2_behavior_tree/plugins/action/truncate_path_action.cpp @@ -67,7 +67,7 @@ inline BT::NodeStatus TruncatePath::tick() if (std::isnan(final_angle) || std::isinf(final_angle)) { RCLCPP_WARN( - config().blackboard->get("node")->get_logger(), + config().blackboard->get("node")->get_logger(), "Final angle is not valid while truncating path. Setting to 0.0"); final_angle = 0.0; } diff --git a/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp b/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp index 271e64added..bf8e58b9184 100644 --- a/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp +++ b/nav2_behavior_tree/plugins/action/truncate_path_local_action.cpp @@ -116,7 +116,7 @@ inline bool TruncatePathLocal::getRobotPose( std::string robot_frame; if (!getInput("robot_frame", robot_frame)) { RCLCPP_ERROR( - config().blackboard->get("node")->get_logger(), + config().blackboard->get("node")->get_logger(), "Neither pose nor robot_frame specified for %s", name().c_str()); return false; } @@ -126,7 +126,7 @@ inline bool TruncatePathLocal::getRobotPose( pose, *tf_buffer_, path_frame_id, robot_frame, transform_tolerance)) { RCLCPP_WARN( - config().blackboard->get("node")->get_logger(), + config().blackboard->get("node")->get_logger(), "Failed to lookup current robot pose for %s", name().c_str()); return false; } diff --git a/nav2_behavior_tree/plugins/condition/are_poses_near_condition.cpp b/nav2_behavior_tree/plugins/condition/are_poses_near_condition.cpp index 4d03f6aaa50..b915f6e5b7a 100644 --- a/nav2_behavior_tree/plugins/condition/are_poses_near_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/are_poses_near_condition.cpp @@ -17,7 +17,7 @@ #include "nav2_util/robot_utils.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_behavior_tree/plugins/condition/are_poses_near_condition.hpp" @@ -29,14 +29,14 @@ ArePosesNearCondition::ArePosesNearCondition( const BT::NodeConfiguration & conf) : BT::ConditionNode(condition_name, conf) { - auto node = config().blackboard->get("node"); + auto node = config().blackboard->get("node"); global_frame_ = BT::deconflictPortAndParamFrame( node, "global_frame", this); } void ArePosesNearCondition::initialize() { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); tf_ = config().blackboard->get>("tf_buffer"); node_->get_parameter("transform_tolerance", transform_tolerance_); } diff --git a/nav2_behavior_tree/plugins/condition/distance_traveled_condition.cpp b/nav2_behavior_tree/plugins/condition/distance_traveled_condition.cpp index 2ebf9c486ea..7a470f6e6c4 100644 --- a/nav2_behavior_tree/plugins/condition/distance_traveled_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/distance_traveled_condition.cpp @@ -37,7 +37,7 @@ void DistanceTraveledCondition::initialize() { getInput("distance", distance_); - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); tf_ = config().blackboard->get>("tf_buffer"); node_->get_parameter("transform_tolerance", transform_tolerance_); diff --git a/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp b/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp index 929f87399db..33ac939ccef 100644 --- a/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/globally_updated_goal_condition.cpp @@ -26,7 +26,7 @@ GloballyUpdatedGoalCondition::GloballyUpdatedGoalCondition( : BT::ConditionNode(condition_name, conf), first_time(true) { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); } BT::NodeStatus GloballyUpdatedGoalCondition::tick() diff --git a/nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp b/nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp index 4b5e20a733e..385dfae6a01 100644 --- a/nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/goal_reached_condition.cpp @@ -17,7 +17,7 @@ #include "nav2_util/robot_utils.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_behavior_tree/plugins/condition/goal_reached_condition.hpp" @@ -29,7 +29,7 @@ GoalReachedCondition::GoalReachedCondition( const BT::NodeConfiguration & conf) : BT::ConditionNode(condition_name, conf) { - auto node = config().blackboard->get("node"); + auto node = config().blackboard->get("node"); robot_base_frame_ = BT::deconflictPortAndParamFrame( node, "robot_base_frame", this); @@ -42,9 +42,9 @@ GoalReachedCondition::~GoalReachedCondition() void GoalReachedCondition::initialize() { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, "goal_reached_tol", rclcpp::ParameterValue(0.25)); node_->get_parameter_or("goal_reached_tol", goal_reached_tol_, 0.25); diff --git a/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp b/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp index 2135e86bf6a..571cf10d64f 100644 --- a/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/is_battery_charging_condition.cpp @@ -45,19 +45,17 @@ void IsBatteryChargingCondition::createROSInterfaces() // Only create a new subscriber if the topic has changed or subscriber is empty if (battery_topic_new != battery_topic_ || !battery_sub_) { battery_topic_ = battery_topic_new; - auto node = config().blackboard->get("node"); + auto node = config().blackboard->get("node"); callback_group_ = node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, node->get_node_base_interface()); - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; battery_sub_ = node->create_subscription( battery_topic_, - rclcpp::SystemDefaultsQoS(), std::bind(&IsBatteryChargingCondition::batteryCallback, this, std::placeholders::_1), - sub_option); + nav2::qos::StandardTopicQoS(), + callback_group_); } } diff --git a/nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp b/nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp index 16130224f59..628b31145b4 100644 --- a/nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/is_battery_low_condition.cpp @@ -51,19 +51,17 @@ void IsBatteryLowCondition::createROSInterfaces() // Only create a new subscriber if the topic has changed or subscriber is empty if (battery_topic_new != battery_topic_ || !battery_sub_) { battery_topic_ = battery_topic_new; - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; battery_sub_ = node_->create_subscription( battery_topic_, - rclcpp::SystemDefaultsQoS(), std::bind(&IsBatteryLowCondition::batteryCallback, this, std::placeholders::_1), - sub_option); + nav2::qos::StandardTopicQoS(), + callback_group_); } } diff --git a/nav2_behavior_tree/plugins/condition/is_path_valid_condition.cpp b/nav2_behavior_tree/plugins/condition/is_path_valid_condition.cpp index ddddc84d76f..5eea22f82c1 100644 --- a/nav2_behavior_tree/plugins/condition/is_path_valid_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/is_path_valid_condition.cpp @@ -26,9 +26,11 @@ IsPathValidCondition::IsPathValidCondition( : BT::ConditionNode(condition_name, conf), max_cost_(254), consider_unknown_as_obstacle_(false) { - node_ = config().blackboard->get("node"); - client_ = std::make_shared>("is_path_valid", - node_, false /* Does not create and spin an internal executor*/); + node_ = config().blackboard->get("node"); + client_ = + node_->create_client( + "is_path_valid", + false /* Does not create and spin an internal executor*/); server_timeout_ = config().blackboard->template get("server_timeout"); } diff --git a/nav2_behavior_tree/plugins/condition/is_stopped_condition.cpp b/nav2_behavior_tree/plugins/condition/is_stopped_condition.cpp index f0b32d4c1c0..c35bbf8133f 100644 --- a/nav2_behavior_tree/plugins/condition/is_stopped_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/is_stopped_condition.cpp @@ -28,7 +28,7 @@ IsStoppedCondition::IsStoppedCondition( duration_stopped_(1000ms), stopped_stamp_(rclcpp::Time(0, 0, RCL_ROS_TIME)) { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); odom_smoother_ = config().blackboard->get>( "odom_smoother"); } diff --git a/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp b/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp index d0ca48cd7f5..88e168441a6 100644 --- a/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/is_stuck_condition.cpp @@ -31,20 +31,18 @@ IsStuckCondition::IsStuckCondition( current_accel_(0.0), brake_accel_limit_(-10.0) { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface()); callback_group_executor_thread = std::thread([this]() {callback_group_executor_.spin();}); - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; odom_sub_ = node_->create_subscription( "odom", - rclcpp::SystemDefaultsQoS(), std::bind(&IsStuckCondition::onOdomReceived, this, std::placeholders::_1), - sub_option); + nav2::qos::StandardTopicQoS(), + callback_group_); RCLCPP_DEBUG(node_->get_logger(), "Initialized an IsStuckCondition BT node"); diff --git a/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.cpp b/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.cpp index 540af1d83d3..99bf9774653 100644 --- a/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/path_expiring_timer_condition.cpp @@ -29,7 +29,7 @@ PathExpiringTimerCondition::PathExpiringTimerCondition( period_(1.0), first_time_(true) { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); } BT::NodeStatus PathExpiringTimerCondition::tick() diff --git a/nav2_behavior_tree/plugins/condition/time_expired_condition.cpp b/nav2_behavior_tree/plugins/condition/time_expired_condition.cpp index 43535565002..ddcc9cfba0d 100644 --- a/nav2_behavior_tree/plugins/condition/time_expired_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/time_expired_condition.cpp @@ -34,7 +34,7 @@ TimeExpiredCondition::TimeExpiredCondition( void TimeExpiredCondition::initialize() { getInput("seconds", period_); - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); start_ = node_->now(); } diff --git a/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp b/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp index 4f84e3e9fc8..b377d47c585 100644 --- a/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp +++ b/nav2_behavior_tree/plugins/condition/transform_available_condition.cpp @@ -33,7 +33,7 @@ TransformAvailableCondition::TransformAvailableCondition( : BT::ConditionNode(condition_name, conf), was_found_(false) { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); tf_ = config().blackboard->get>("tf_buffer"); } diff --git a/nav2_behavior_tree/plugins/decorator/distance_controller.cpp b/nav2_behavior_tree/plugins/decorator/distance_controller.cpp index 4d0f6fefef0..0fdd47e7ffb 100644 --- a/nav2_behavior_tree/plugins/decorator/distance_controller.cpp +++ b/nav2_behavior_tree/plugins/decorator/distance_controller.cpp @@ -38,7 +38,7 @@ DistanceController::DistanceController( first_time_(false) { getInput("distance", distance_); - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); tf_ = config().blackboard->get>("tf_buffer"); node_->get_parameter("transform_tolerance", transform_tolerance_); diff --git a/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp b/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp index 2e445c6a3e7..2cf6031ce19 100644 --- a/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp +++ b/nav2_behavior_tree/plugins/decorator/goal_updater_node.cpp @@ -48,7 +48,7 @@ void GoalUpdater::initialize() void GoalUpdater::createROSInterfaces() { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); callback_group_ = node_->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); @@ -63,23 +63,19 @@ void GoalUpdater::createROSInterfaces() // Only create a new subscriber if the topic has changed or subscriber is empty if (goal_updater_topic_new != goal_updater_topic_ || !goal_sub_) { goal_updater_topic_ = goal_updater_topic_new; - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; goal_sub_ = node_->create_subscription( goal_updater_topic_, - rclcpp::SystemDefaultsQoS(), std::bind(&GoalUpdater::callback_updated_goal, this, _1), - sub_option); + nav2::qos::StandardTopicQoS(), + callback_group_); } if (goals_updater_topic_new != goals_updater_topic_ || !goals_sub_) { goals_updater_topic_ = goals_updater_topic_new; - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; goals_sub_ = node_->create_subscription( goals_updater_topic_, - rclcpp::SystemDefaultsQoS(), std::bind(&GoalUpdater::callback_updated_goals, this, _1), - sub_option); + nav2::qos::StandardTopicQoS(), + callback_group_); } } diff --git a/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.cpp b/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.cpp index 443a29acf02..aee651690e3 100644 --- a/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.cpp +++ b/nav2_behavior_tree/plugins/decorator/path_longer_on_approach.cpp @@ -27,7 +27,7 @@ PathLongerOnApproach::PathLongerOnApproach( const BT::NodeConfiguration & conf) : BT::DecoratorNode(name, conf) { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); } bool PathLongerOnApproach::isPathUpdated( diff --git a/nav2_behavior_tree/plugins/decorator/speed_controller.cpp b/nav2_behavior_tree/plugins/decorator/speed_controller.cpp index b6891108861..1eb5c50fcb0 100644 --- a/nav2_behavior_tree/plugins/decorator/speed_controller.cpp +++ b/nav2_behavior_tree/plugins/decorator/speed_controller.cpp @@ -34,7 +34,7 @@ SpeedController::SpeedController( min_speed_(0.0), max_speed_(0.5) { - node_ = config().blackboard->get("node"); + node_ = config().blackboard->get("node"); getInput("min_rate", min_rate_); getInput("max_rate", max_rate_); diff --git a/nav2_behavior_tree/src/behavior_tree_engine.cpp b/nav2_behavior_tree/src/behavior_tree_engine.cpp index 782a9660a8c..21131be010a 100644 --- a/nav2_behavior_tree/src/behavior_tree_engine.cpp +++ b/nav2_behavior_tree/src/behavior_tree_engine.cpp @@ -29,7 +29,8 @@ namespace nav2_behavior_tree { BehaviorTreeEngine::BehaviorTreeEngine( - const std::vector & plugin_libraries, rclcpp::Node::SharedPtr node) + const std::vector & plugin_libraries, + const nav2::LifecycleNode::SharedPtr node) { BT::SharedLibrary loader; for (const auto & p : plugin_libraries) { diff --git a/nav2_behavior_tree/test/plugins/action/test_append_goal_pose_to_goals_action.cpp b/nav2_behavior_tree/test/plugins/action/test_append_goal_pose_to_goals_action.cpp index f6cb4baadd5..cffda5cd5f6 100644 --- a/nav2_behavior_tree/test/plugins/action/test_append_goal_pose_to_goals_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_append_goal_pose_to_goals_action.cpp @@ -33,7 +33,7 @@ class AppendGoalPoseToGoalsTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_fixture"); + node_ = std::make_shared("test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -77,14 +77,14 @@ class AppendGoalPoseToGoalsTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; static std::shared_ptr transform_handler_; }; -rclcpp::Node::SharedPtr AppendGoalPoseToGoalsTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr AppendGoalPoseToGoalsTestFixture::node_ = nullptr; BT::NodeConfiguration * AppendGoalPoseToGoalsTestFixture::config_ = nullptr; std::shared_ptr AppendGoalPoseToGoalsTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_action.cpp b/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_action.cpp index 7968545870f..1d5fa75301f 100644 --- a/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_action.cpp @@ -52,7 +52,7 @@ class AssistedTeleopActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("backup_action_test_fixture"); + node_ = std::make_shared("backup_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -106,13 +106,13 @@ class AssistedTeleopActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr AssistedTeleopActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr AssistedTeleopActionTestFixture::node_ = nullptr; std::shared_ptr AssistedTeleopActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * AssistedTeleopActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_cancel_node.cpp b/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_cancel_node.cpp index 0db8e1a3774..9137b78d0f8 100644 --- a/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_cancel_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_assisted_teleop_cancel_node.cpp @@ -48,7 +48,7 @@ class CancelAssistedTeleopActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("cancel_back_up_action_test_fixture"); + node_ = std::make_shared("cancel_back_up_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -98,19 +98,19 @@ class CancelAssistedTeleopActionTestFixture : public ::testing::Test } static std::shared_ptr action_server_; - static std::shared_ptr> client_; + static std::shared_ptr> client_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr CancelAssistedTeleopActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr CancelAssistedTeleopActionTestFixture::node_ = nullptr; std::shared_ptr CancelAssistedTeleopActionTestFixture::action_server_ = nullptr; -std::shared_ptr> +std::shared_ptr> CancelAssistedTeleopActionTestFixture::client_ = nullptr; BT::NodeConfiguration * CancelAssistedTeleopActionTestFixture::config_ = nullptr; @@ -129,7 +129,7 @@ TEST_F(CancelAssistedTeleopActionTestFixture, test_ports) )"; tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); - auto send_goal_options = rclcpp_action::Client< + auto send_goal_options = nav2::ActionClient< nav2_msgs::action::AssistedTeleop>::SendGoalOptions(); // Creating a dummy goal_msg diff --git a/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp b/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp index 98484bde8cb..c883b2c219a 100644 --- a/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_back_up_action.cpp @@ -52,7 +52,7 @@ class BackUpActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("backup_action_test_fixture"); + node_ = std::make_shared("backup_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -106,13 +106,13 @@ class BackUpActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr BackUpActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr BackUpActionTestFixture::node_ = nullptr; std::shared_ptr BackUpActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * BackUpActionTestFixture::config_ = nullptr; std::shared_ptr BackUpActionTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_back_up_cancel_node.cpp b/nav2_behavior_tree/test/plugins/action/test_back_up_cancel_node.cpp index cbc45e3c09d..e01af2291d6 100644 --- a/nav2_behavior_tree/test/plugins/action/test_back_up_cancel_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_back_up_cancel_node.cpp @@ -47,7 +47,7 @@ class CancelBackUpActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("cancel_back_up_action_test_fixture"); + node_ = std::make_shared("cancel_back_up_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -96,19 +96,19 @@ class CancelBackUpActionTestFixture : public ::testing::Test } static std::shared_ptr action_server_; - static std::shared_ptr> client_; + static std::shared_ptr> client_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr CancelBackUpActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr CancelBackUpActionTestFixture::node_ = nullptr; std::shared_ptr CancelBackUpActionTestFixture::action_server_ = nullptr; -std::shared_ptr> +std::shared_ptr> CancelBackUpActionTestFixture::client_ = nullptr; BT::NodeConfiguration * CancelBackUpActionTestFixture::config_ = nullptr; @@ -127,7 +127,7 @@ TEST_F(CancelBackUpActionTestFixture, test_ports) )"; tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); // Creating a dummy goal_msg auto goal_msg = nav2_msgs::action::BackUp::Goal(); diff --git a/nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp b/nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp index 56a66a4602c..3b2a3b382c1 100644 --- a/nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp @@ -163,7 +163,7 @@ class BTActionNodeTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("bt_action_node_test_fixture"); + node_ = std::make_shared("bt_action_node_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -220,14 +220,14 @@ class BTActionNodeTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; static std::shared_ptr server_thread_; }; -rclcpp::Node::SharedPtr BTActionNodeTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr BTActionNodeTestFixture::node_ = nullptr; std::shared_ptr BTActionNodeTestFixture::action_server_ = nullptr; BT::NodeConfiguration * BTActionNodeTestFixture::config_ = nullptr; std::shared_ptr BTActionNodeTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp b/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp index 76f3b1d025a..f63a5007c1e 100644 --- a/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_clear_costmap_service.cpp @@ -36,7 +36,7 @@ class ClearEntireCostmapServiceTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("clear_entire_costmap_test_fixture"); + node_ = std::make_shared("clear_entire_costmap_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -84,13 +84,13 @@ class ClearEntireCostmapServiceTestFixture : public ::testing::Test static std::shared_ptr server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ClearEntireCostmapServiceTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ClearEntireCostmapServiceTestFixture::node_ = nullptr; std::shared_ptr ClearEntireCostmapServiceTestFixture::server_ = nullptr; BT::NodeConfiguration * ClearEntireCostmapServiceTestFixture::config_ = nullptr; std::shared_ptr ClearEntireCostmapServiceTestFixture::factory_ = nullptr; @@ -125,7 +125,7 @@ class ClearCostmapExceptRegionServiceTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("clear_costmap_except_region_test_fixture"); + node_ = std::make_shared("clear_costmap_except_region_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -174,13 +174,13 @@ class ClearCostmapExceptRegionServiceTestFixture : public ::testing::Test static std::shared_ptr server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr +nav2::LifecycleNode::SharedPtr ClearCostmapExceptRegionServiceTestFixture::node_ = nullptr; std::shared_ptr ClearCostmapExceptRegionServiceTestFixture::server_ = nullptr; @@ -220,7 +220,7 @@ class ClearCostmapAroundRobotServiceTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("clear_costmap_around_robot_test_fixture"); + node_ = std::make_shared("clear_costmap_around_robot_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -269,13 +269,13 @@ class ClearCostmapAroundRobotServiceTestFixture : public ::testing::Test static std::shared_ptr server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr +nav2::LifecycleNode::SharedPtr ClearCostmapAroundRobotServiceTestFixture::node_ = nullptr; std::shared_ptr ClearCostmapAroundRobotServiceTestFixture::server_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_action.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_action.cpp index 0129eb46359..289b1b794c1 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_action.cpp @@ -51,7 +51,7 @@ class ComputeAndTrackRouteActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("follow_path_action_test_fixture"); + node_ = std::make_shared("follow_path_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -101,13 +101,13 @@ class ComputeAndTrackRouteActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ComputeAndTrackRouteActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ComputeAndTrackRouteActionTestFixture::node_ = nullptr; std::shared_ptr ComputeAndTrackRouteActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * ComputeAndTrackRouteActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_cancel_node.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_cancel_node.cpp index de94f9c47a1..876c2cbd983 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_cancel_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_and_track_route_cancel_node.cpp @@ -49,7 +49,8 @@ class CancelComputeAndTrackRouteActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("cancel_compute_and_track_route_action_test_fixture"); + node_ = + std::make_shared("cancel_compute_and_track_route_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -99,19 +100,19 @@ class CancelComputeAndTrackRouteActionTestFixture : public ::testing::Test } static std::shared_ptr action_server_; - static std::shared_ptr> client_; + static std::shared_ptr> client_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr CancelComputeAndTrackRouteActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr CancelComputeAndTrackRouteActionTestFixture::node_ = nullptr; std::shared_ptr CancelComputeAndTrackRouteActionTestFixture::action_server_ = nullptr; -std::shared_ptr> +std::shared_ptr> CancelComputeAndTrackRouteActionTestFixture::client_ = nullptr; BT::NodeConfiguration * CancelComputeAndTrackRouteActionTestFixture::config_ = nullptr; @@ -130,7 +131,7 @@ TEST_F(CancelComputeAndTrackRouteActionTestFixture, test_ports) )"; tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); - auto send_goal_options = rclcpp_action::Client< + auto send_goal_options = nav2::ActionClient< nav2_msgs::action::ComputeAndTrackRoute>::SendGoalOptions(); // Creating a dummy goal_msg diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp index 550047e56e2..e9b98261781 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_path_through_poses_action.cpp @@ -59,7 +59,7 @@ class ComputePathThroughPosesActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("compute_path_through_poses_action_test_fixture"); + node_ = std::make_shared("compute_path_through_poses_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -109,13 +109,13 @@ class ComputePathThroughPosesActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ComputePathThroughPosesActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ComputePathThroughPosesActionTestFixture::node_ = nullptr; std::shared_ptr ComputePathThroughPosesActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * ComputePathThroughPosesActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp index 4f03c3b59bd..3d022205ee0 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_path_to_pose_action.cpp @@ -57,7 +57,7 @@ class ComputePathToPoseActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("compute_path_to_pose_action_test_fixture"); + node_ = std::make_shared("compute_path_to_pose_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -107,13 +107,13 @@ class ComputePathToPoseActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ComputePathToPoseActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ComputePathToPoseActionTestFixture::node_ = nullptr; std::shared_ptr ComputePathToPoseActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * ComputePathToPoseActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_compute_route_action.cpp b/nav2_behavior_tree/test/plugins/action/test_compute_route_action.cpp index 308e68727f9..d1d4df19870 100644 --- a/nav2_behavior_tree/test/plugins/action/test_compute_route_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_compute_route_action.cpp @@ -59,7 +59,7 @@ class ComputeRouteActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("compute_path_to_pose_action_test_fixture"); + node_ = std::make_shared("compute_path_to_pose_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -109,13 +109,13 @@ class ComputeRouteActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ComputeRouteActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ComputeRouteActionTestFixture::node_ = nullptr; std::shared_ptr ComputeRouteActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * ComputeRouteActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_concatenate_paths_action.cpp b/nav2_behavior_tree/test/plugins/action/test_concatenate_paths_action.cpp index f8c6802e51d..90613e1497f 100644 --- a/nav2_behavior_tree/test/plugins/action/test_concatenate_paths_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_concatenate_paths_action.cpp @@ -36,7 +36,7 @@ class ConcatenatePathsTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_fixture"); + node_ = std::make_shared("test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -73,13 +73,13 @@ class ConcatenatePathsTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ConcatenatePathsTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ConcatenatePathsTestFixture::node_ = nullptr; BT::NodeConfiguration * ConcatenatePathsTestFixture::config_ = nullptr; std::shared_ptr ConcatenatePathsTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_controller_cancel_node.cpp b/nav2_behavior_tree/test/plugins/action/test_controller_cancel_node.cpp index 5b9ad922c98..e13661e9e25 100644 --- a/nav2_behavior_tree/test/plugins/action/test_controller_cancel_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_controller_cancel_node.cpp @@ -47,7 +47,7 @@ class CancelControllerActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("cancel_control_action_test_fixture"); + node_ = std::make_shared("cancel_control_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -96,19 +96,19 @@ class CancelControllerActionTestFixture : public ::testing::Test } static std::shared_ptr action_server_; - static std::shared_ptr> client_; + static std::shared_ptr> client_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr CancelControllerActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr CancelControllerActionTestFixture::node_ = nullptr; std::shared_ptr CancelControllerActionTestFixture::action_server_ = nullptr; -std::shared_ptr> +std::shared_ptr> CancelControllerActionTestFixture::client_ = nullptr; BT::NodeConfiguration * CancelControllerActionTestFixture::config_ = nullptr; @@ -127,7 +127,7 @@ TEST_F(CancelControllerActionTestFixture, test_ports) )"; tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); // Creating a dummy goal_msg auto goal_msg = nav2_msgs::action::FollowPath::Goal(); diff --git a/nav2_behavior_tree/test/plugins/action/test_controller_selector_node.cpp b/nav2_behavior_tree/test/plugins/action/test_controller_selector_node.cpp index 743378561de..ec1abd18e59 100644 --- a/nav2_behavior_tree/test/plugins/action/test_controller_selector_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_controller_selector_node.cpp @@ -30,7 +30,12 @@ class ControllerSelectorTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("controller_selector_test_fixture"); + node_ = std::make_shared("controller_selector_test_fixture"); + + // Configure and activate the lifecycle node + node_->configure(); + node_->activate(); + factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -51,6 +56,10 @@ class ControllerSelectorTestFixture : public ::testing::Test static void TearDownTestCase() { + // Properly deactivate and cleanup the lifecycle node + node_->deactivate(); + node_->cleanup(); + delete config_; config_ = nullptr; node_.reset(); @@ -63,13 +72,13 @@ class ControllerSelectorTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ControllerSelectorTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ControllerSelectorTestFixture::node_ = nullptr; BT::NodeConfiguration * ControllerSelectorTestFixture::config_ = nullptr; std::shared_ptr ControllerSelectorTestFixture::factory_ = nullptr; @@ -103,11 +112,10 @@ TEST_F(ControllerSelectorTestFixture, test_custom_topic) selected_controller_cmd.data = "DWC"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); - auto controller_selector_pub = - node_->create_publisher("controller_selector_custom_topic_name", qos); + node_->create_publisher( + "controller_selector_custom_topic_name", nav2::qos::LatchedPublisherQoS()); + controller_selector_pub->on_activate(); // publish a few updates of the selected_controller auto start = node_->now(); @@ -115,7 +123,7 @@ TEST_F(ControllerSelectorTestFixture, test_custom_topic) tree_->rootNode()->executeTick(); controller_selector_pub->publish(selected_controller_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check controller updated @@ -151,11 +159,10 @@ TEST_F(ControllerSelectorTestFixture, test_default_topic) selected_controller_cmd.data = "RRT"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); - auto controller_selector_pub = - node_->create_publisher("controller_selector", qos); + node_->create_publisher( + "controller_selector", nav2::qos::LatchedPublisherQoS()); + controller_selector_pub->on_activate(); // publish a few updates of the selected_controller auto start = node_->now(); @@ -163,7 +170,7 @@ TEST_F(ControllerSelectorTestFixture, test_default_topic) tree_->rootNode()->executeTick(); controller_selector_pub->publish(selected_controller_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check controller updated diff --git a/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_action.cpp b/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_action.cpp index 0c53fd54c8f..18d76397db9 100644 --- a/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_action.cpp @@ -53,7 +53,7 @@ class DriveOnHeadingActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("drive_on_heading_action_test_fixture"); + node_ = std::make_shared("drive_on_heading_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -101,13 +101,13 @@ class DriveOnHeadingActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr DriveOnHeadingActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr DriveOnHeadingActionTestFixture::node_ = nullptr; std::shared_ptr DriveOnHeadingActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * DriveOnHeadingActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_cancel_node.cpp b/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_cancel_node.cpp index 346342a67bc..3c677772751 100644 --- a/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_cancel_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_drive_on_heading_cancel_node.cpp @@ -48,7 +48,7 @@ class CancelDriveOnHeadingTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("cancel_drive_on_heading_action_test_fixture"); + node_ = std::make_shared("cancel_drive_on_heading_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -99,19 +99,19 @@ class CancelDriveOnHeadingTestFixture : public ::testing::Test } static std::shared_ptr action_server_; - static std::shared_ptr> client_; + static std::shared_ptr> client_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr CancelDriveOnHeadingTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr CancelDriveOnHeadingTestFixture::node_ = nullptr; std::shared_ptr CancelDriveOnHeadingTestFixture::action_server_ = nullptr; -std::shared_ptr> +std::shared_ptr> CancelDriveOnHeadingTestFixture::client_ = nullptr; BT::NodeConfiguration * CancelDriveOnHeadingTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_extract_route_nodes_as_goals_action.cpp b/nav2_behavior_tree/test/plugins/action/test_extract_route_nodes_as_goals_action.cpp index 6c541fc9de5..8aaef5848e9 100644 --- a/nav2_behavior_tree/test/plugins/action/test_extract_route_nodes_as_goals_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_extract_route_nodes_as_goals_action.cpp @@ -33,7 +33,7 @@ class ExtractRouteNodesAsGoalsTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_fixture"); + node_ = std::make_shared("test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -77,14 +77,14 @@ class ExtractRouteNodesAsGoalsTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; static std::shared_ptr transform_handler_; }; -rclcpp::Node::SharedPtr ExtractRouteNodesAsGoalsTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ExtractRouteNodesAsGoalsTestFixture::node_ = nullptr; BT::NodeConfiguration * ExtractRouteNodesAsGoalsTestFixture::config_ = nullptr; std::shared_ptr ExtractRouteNodesAsGoalsTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp index 32c3b1ffbf8..d25de596e34 100644 --- a/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_follow_path_action.cpp @@ -50,7 +50,7 @@ class FollowPathActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("follow_path_action_test_fixture"); + node_ = std::make_shared("follow_path_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -100,13 +100,13 @@ class FollowPathActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr FollowPathActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr FollowPathActionTestFixture::node_ = nullptr; std::shared_ptr FollowPathActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * FollowPathActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_get_current_pose_action.cpp b/nav2_behavior_tree/test/plugins/action/test_get_current_pose_action.cpp index 495d112aa0d..7d23478a434 100644 --- a/nav2_behavior_tree/test/plugins/action/test_get_current_pose_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_get_current_pose_action.cpp @@ -26,7 +26,7 @@ #include "nav2_behavior_tree/utils/test_action_server.hpp" #include "nav2_behavior_tree/plugins/action/get_current_pose_action.hpp" #include "utils/test_behavior_tree_fixture.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" class GetCurrentPoseTestFixture : public nav2_behavior_tree::BehaviorTreeTestFixture { @@ -35,9 +35,9 @@ class GetCurrentPoseTestFixture : public nav2_behavior_tree::BehaviorTreeTestFix { config_->blackboard->set("robot_base_frame", "base_link"); config_->blackboard->set("global_frame", "map"); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, "robot_base_frame", rclcpp::ParameterValue("base_link")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, "global_frame", rclcpp::ParameterValue("map")); BT::NodeBuilder builder = diff --git a/nav2_behavior_tree/test/plugins/action/test_get_next_few_goals_action.cpp b/nav2_behavior_tree/test/plugins/action/test_get_next_few_goals_action.cpp index 4926711d333..8578decc322 100644 --- a/nav2_behavior_tree/test/plugins/action/test_get_next_few_goals_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_get_next_few_goals_action.cpp @@ -33,7 +33,7 @@ class GetNextFewGoalsTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_fixture"); + node_ = std::make_shared("test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -77,14 +77,14 @@ class GetNextFewGoalsTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; static std::shared_ptr transform_handler_; }; -rclcpp::Node::SharedPtr GetNextFewGoalsTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr GetNextFewGoalsTestFixture::node_ = nullptr; BT::NodeConfiguration * GetNextFewGoalsTestFixture::config_ = nullptr; std::shared_ptr GetNextFewGoalsTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp index 2e9fcbceadd..d2ff9bb291b 100644 --- a/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_get_pose_from_path_action.cpp @@ -34,7 +34,7 @@ class GetPoseFromPathTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("get_pose_from_path_action_test_fixture"); + node_ = std::make_shared("get_pose_from_path_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -42,7 +42,7 @@ class GetPoseFromPathTestFixture : public ::testing::Test // Create the blackboard that will be shared by all of the nodes in the tree config_->blackboard = BT::Blackboard::create(); // Put items on the blackboard - config_->blackboard->set( + config_->blackboard->set( "node", node_); @@ -71,13 +71,13 @@ class GetPoseFromPathTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr GetPoseFromPathTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr GetPoseFromPathTestFixture::node_ = nullptr; BT::NodeConfiguration * GetPoseFromPathTestFixture::config_ = nullptr; std::shared_ptr GetPoseFromPathTestFixture::factory_ = nullptr; std::shared_ptr GetPoseFromPathTestFixture::tree_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_goal_checker_selector_node.cpp b/nav2_behavior_tree/test/plugins/action/test_goal_checker_selector_node.cpp index 92900c4a5f1..fb4a40c0ffc 100644 --- a/nav2_behavior_tree/test/plugins/action/test_goal_checker_selector_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_goal_checker_selector_node.cpp @@ -30,7 +30,12 @@ class GoalCheckerSelectorTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("goal_checker_selector_test_fixture"); + node_ = std::make_shared("goal_checker_selector_test_fixture"); + + // Configure and activate the lifecycle node + node_->configure(); + node_->activate(); + factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -51,6 +56,10 @@ class GoalCheckerSelectorTestFixture : public ::testing::Test static void TearDownTestCase() { + // Properly deactivate and cleanup the lifecycle node + node_->deactivate(); + node_->cleanup(); + delete config_; config_ = nullptr; node_.reset(); @@ -63,13 +72,13 @@ class GoalCheckerSelectorTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr GoalCheckerSelectorTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr GoalCheckerSelectorTestFixture::node_ = nullptr; BT::NodeConfiguration * GoalCheckerSelectorTestFixture::config_ = nullptr; std::shared_ptr GoalCheckerSelectorTestFixture::factory_ = nullptr; @@ -103,11 +112,11 @@ TEST_F(GoalCheckerSelectorTestFixture, test_custom_topic) selected_goal_checker_cmd.data = "AngularGoalChecker"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto goal_checker_selector_pub = node_->create_publisher("goal_checker_selector_custom_topic_name", qos); + goal_checker_selector_pub->on_activate(); // publish a few updates of the selected_goal_checker auto start = node_->now(); @@ -115,7 +124,7 @@ TEST_F(GoalCheckerSelectorTestFixture, test_custom_topic) tree_->rootNode()->executeTick(); goal_checker_selector_pub->publish(selected_goal_checker_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check goal_checker updated @@ -151,11 +160,11 @@ TEST_F(GoalCheckerSelectorTestFixture, test_default_topic) selected_goal_checker_cmd.data = "RRT"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto goal_checker_selector_pub = node_->create_publisher("goal_checker_selector", qos); + goal_checker_selector_pub->on_activate(); // publish a few updates of the selected_goal_checker auto start = node_->now(); @@ -163,7 +172,7 @@ TEST_F(GoalCheckerSelectorTestFixture, test_default_topic) tree_->rootNode()->executeTick(); goal_checker_selector_pub->publish(selected_goal_checker_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check goal_checker updated diff --git a/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp b/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp index f73dca6ac28..7b1ff5f5572 100644 --- a/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_navigate_through_poses_action.cpp @@ -53,7 +53,7 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("navigate_through_poses_action_test_fixture"); + node_ = std::make_shared("navigate_through_poses_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -106,13 +106,13 @@ class NavigateThroughPosesActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr NavigateThroughPosesActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr NavigateThroughPosesActionTestFixture::node_ = nullptr; std::shared_ptr NavigateThroughPosesActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * NavigateThroughPosesActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp b/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp index d6a31ab4eb8..46465169655 100644 --- a/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_navigate_to_pose_action.cpp @@ -51,7 +51,7 @@ class NavigateToPoseActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("navigate_to_pose_action_test_fixture"); + node_ = std::make_shared("navigate_to_pose_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -101,13 +101,13 @@ class NavigateToPoseActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr NavigateToPoseActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr NavigateToPoseActionTestFixture::node_ = nullptr; std::shared_ptr NavigateToPoseActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * NavigateToPoseActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_planner_selector_node.cpp b/nav2_behavior_tree/test/plugins/action/test_planner_selector_node.cpp index 7ca442d9114..3308abe5efa 100644 --- a/nav2_behavior_tree/test/plugins/action/test_planner_selector_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_planner_selector_node.cpp @@ -30,7 +30,12 @@ class PlannerSelectorTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("planner_selector_test_fixture"); + node_ = std::make_shared("planner_selector_test_fixture"); + + // Configure and activate the lifecycle node + node_->configure(); + node_->activate(); + factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -49,6 +54,10 @@ class PlannerSelectorTestFixture : public ::testing::Test static void TearDownTestCase() { + // Properly deactivate and cleanup the lifecycle node + node_->deactivate(); + node_->cleanup(); + delete config_; config_ = nullptr; node_.reset(); @@ -61,13 +70,13 @@ class PlannerSelectorTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr PlannerSelectorTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr PlannerSelectorTestFixture::node_ = nullptr; BT::NodeConfiguration * PlannerSelectorTestFixture::config_ = nullptr; std::shared_ptr PlannerSelectorTestFixture::factory_ = nullptr; @@ -101,11 +110,11 @@ TEST_F(PlannerSelectorTestFixture, test_custom_topic) selected_planner_cmd.data = "RRT"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto planner_selector_pub = node_->create_publisher("planner_selector_custom_topic_name", qos); + planner_selector_pub->on_activate(); // publish a few updates of the selected_planner auto start = node_->now(); @@ -113,7 +122,7 @@ TEST_F(PlannerSelectorTestFixture, test_custom_topic) tree_->rootNode()->executeTick(); planner_selector_pub->publish(selected_planner_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check planner updated @@ -149,11 +158,11 @@ TEST_F(PlannerSelectorTestFixture, test_default_topic) selected_planner_cmd.data = "RRT"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto planner_selector_pub = node_->create_publisher("planner_selector", qos); + planner_selector_pub->on_activate(); // publish a few updates of the selected_planner auto start = node_->now(); @@ -161,7 +170,7 @@ TEST_F(PlannerSelectorTestFixture, test_default_topic) tree_->rootNode()->executeTick(); planner_selector_pub->publish(selected_planner_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check planner updated diff --git a/nav2_behavior_tree/test/plugins/action/test_progress_checker_selector_node.cpp b/nav2_behavior_tree/test/plugins/action/test_progress_checker_selector_node.cpp index 614f75a4c3a..c7c70e742e9 100644 --- a/nav2_behavior_tree/test/plugins/action/test_progress_checker_selector_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_progress_checker_selector_node.cpp @@ -29,7 +29,12 @@ class ProgressCheckerSelectorTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("progress_checker_selector_test_fixture"); + node_ = std::make_shared("progress_checker_selector_test_fixture"); + + // Configure and activate the lifecycle node + node_->configure(); + node_->activate(); + factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -50,6 +55,10 @@ class ProgressCheckerSelectorTestFixture : public ::testing::Test static void TearDownTestCase() { + // Properly deactivate and cleanup the lifecycle node + node_->deactivate(); + node_->cleanup(); + delete config_; config_ = nullptr; node_.reset(); @@ -62,13 +71,13 @@ class ProgressCheckerSelectorTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ProgressCheckerSelectorTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ProgressCheckerSelectorTestFixture::node_ = nullptr; BT::NodeConfiguration * ProgressCheckerSelectorTestFixture::config_ = nullptr; std::shared_ptr ProgressCheckerSelectorTestFixture::factory_ = nullptr; @@ -104,12 +113,12 @@ TEST_F(ProgressCheckerSelectorTestFixture, test_custom_topic) selected_progress_checker_cmd.data = "AngularProgressChecker"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto progress_checker_selector_pub = node_->create_publisher( "progress_checker_selector_custom_topic_name", qos); + progress_checker_selector_pub->on_activate(); // publish a few updates of the selected_progress_checker auto start = node_->now(); @@ -117,7 +126,7 @@ TEST_F(ProgressCheckerSelectorTestFixture, test_custom_topic) tree_->rootNode()->executeTick(); progress_checker_selector_pub->publish(selected_progress_checker_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check progress_checker updated @@ -155,11 +164,11 @@ TEST_F(ProgressCheckerSelectorTestFixture, test_default_topic) selected_progress_checker_cmd.data = "RRT"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto progress_checker_selector_pub = node_->create_publisher("progress_checker_selector", qos); + progress_checker_selector_pub->on_activate(); // publish a few updates of the selected_progress_checker auto start = node_->now(); @@ -167,7 +176,7 @@ TEST_F(ProgressCheckerSelectorTestFixture, test_default_topic) tree_->rootNode()->executeTick(); progress_checker_selector_pub->publish(selected_progress_checker_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check goal_checker updated diff --git a/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp b/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp index 04b0e704903..d5fb61788b9 100644 --- a/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_reinitialize_global_localization_service.cpp @@ -36,7 +36,7 @@ class ReinitializeGlobalLocalizationServiceTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("reinitialize_global_localization_test_fixture"); + node_ = std::make_shared("reinitialize_global_localization_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -79,13 +79,13 @@ class ReinitializeGlobalLocalizationServiceTestFixture : public ::testing::Test static std::shared_ptr server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr ReinitializeGlobalLocalizationServiceTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr ReinitializeGlobalLocalizationServiceTestFixture::node_ = nullptr; std::shared_ptr ReinitializeGlobalLocalizationServiceTestFixture::server_ = nullptr; BT::NodeConfiguration * ReinitializeGlobalLocalizationServiceTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp b/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp index 9ddb24e494a..fa252070685 100644 --- a/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_remove_in_collision_goals_action.cpp @@ -68,7 +68,7 @@ class RemoveInCollisionGoalsTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("in_collision_goals_test_fixture"); + node_ = std::make_shared("in_collision_goals_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -118,13 +118,13 @@ class RemoveInCollisionGoalsTestFixture : public ::testing::Test static std::shared_ptr failure_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr RemoveInCollisionGoalsTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr RemoveInCollisionGoalsTestFixture::node_ = nullptr; BT::NodeConfiguration * RemoveInCollisionGoalsTestFixture::config_ = nullptr; std::shared_ptr diff --git a/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp b/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp index b82e5c678c9..95ec8810415 100644 --- a/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_remove_passed_goals_action.cpp @@ -34,7 +34,7 @@ class RemovePassedGoalsTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("passed_goals_test_fixture"); + node_ = std::make_shared("passed_goals_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -78,14 +78,14 @@ class RemovePassedGoalsTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; static std::shared_ptr transform_handler_; }; -rclcpp::Node::SharedPtr RemovePassedGoalsTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr RemovePassedGoalsTestFixture::node_ = nullptr; BT::NodeConfiguration * RemovePassedGoalsTestFixture::config_ = nullptr; std::shared_ptr RemovePassedGoalsTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_smooth_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_smooth_path_action.cpp index 60c68b980d9..78fee49c62f 100644 --- a/nav2_behavior_tree/test/plugins/action/test_smooth_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_smooth_path_action.cpp @@ -50,7 +50,7 @@ class SmoothPathActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("smooth_path_action_test_fixture"); + node_ = std::make_shared("smooth_path_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -100,13 +100,13 @@ class SmoothPathActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr SmoothPathActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr SmoothPathActionTestFixture::node_ = nullptr; std::shared_ptr SmoothPathActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * SmoothPathActionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_smoother_selector_node.cpp b/nav2_behavior_tree/test/plugins/action/test_smoother_selector_node.cpp index a6cd7b19baf..002610472f4 100644 --- a/nav2_behavior_tree/test/plugins/action/test_smoother_selector_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_smoother_selector_node.cpp @@ -30,7 +30,12 @@ class SmootherSelectorTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("smoother_selector_test_fixture"); + node_ = std::make_shared("smoother_selector_test_fixture"); + + // Configure and activate the lifecycle node + node_->configure(); + node_->activate(); + factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -51,6 +56,10 @@ class SmootherSelectorTestFixture : public ::testing::Test static void TearDownTestCase() { + // Properly deactivate and cleanup the lifecycle node + node_->deactivate(); + node_->cleanup(); + delete config_; config_ = nullptr; node_.reset(); @@ -63,13 +72,13 @@ class SmootherSelectorTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr SmootherSelectorTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr SmootherSelectorTestFixture::node_ = nullptr; BT::NodeConfiguration * SmootherSelectorTestFixture::config_ = nullptr; std::shared_ptr SmootherSelectorTestFixture::factory_ = nullptr; @@ -103,11 +112,11 @@ TEST_F(SmootherSelectorTestFixture, test_custom_topic) selected_smoother_cmd.data = "DWC"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto smoother_selector_pub = node_->create_publisher("smoother_selector_custom_topic_name", qos); + smoother_selector_pub->on_activate(); // publish a few updates of the selected_smoother auto start = node_->now(); @@ -115,7 +124,7 @@ TEST_F(SmootherSelectorTestFixture, test_custom_topic) tree_->rootNode()->executeTick(); smoother_selector_pub->publish(selected_smoother_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check smoother updated @@ -151,11 +160,11 @@ TEST_F(SmootherSelectorTestFixture, test_default_topic) selected_smoother_cmd.data = "RRT"; - rclcpp::QoS qos(rclcpp::KeepLast(1)); - qos.transient_local().reliable(); + rclcpp::QoS qos = nav2::qos::LatchedPublisherQoS(); auto smoother_selector_pub = node_->create_publisher("smoother_selector", qos); + smoother_selector_pub->on_activate(); // publish a few updates of the selected_smoother auto start = node_->now(); @@ -163,7 +172,7 @@ TEST_F(SmootherSelectorTestFixture, test_default_topic) tree_->rootNode()->executeTick(); smoother_selector_pub->publish(selected_smoother_cmd); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); } // check smoother updated diff --git a/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp b/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp index 134e9dc9c12..af4a5cbac8a 100644 --- a/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_spin_action.cpp @@ -52,7 +52,7 @@ class SpinActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("spin_action_test_fixture"); + node_ = std::make_shared("spin_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -106,13 +106,13 @@ class SpinActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr SpinActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr SpinActionTestFixture::node_ = nullptr; std::shared_ptr SpinActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * SpinActionTestFixture::config_ = nullptr; std::shared_ptr SpinActionTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_spin_cancel_node.cpp b/nav2_behavior_tree/test/plugins/action/test_spin_cancel_node.cpp index 9a37bffab54..60267c6e844 100644 --- a/nav2_behavior_tree/test/plugins/action/test_spin_cancel_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_spin_cancel_node.cpp @@ -47,7 +47,7 @@ class CancelSpinActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("cancel_spin_action_test_fixture"); + node_ = std::make_shared("cancel_spin_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -96,19 +96,19 @@ class CancelSpinActionTestFixture : public ::testing::Test } static std::shared_ptr action_server_; - static std::shared_ptr> client_; + static std::shared_ptr> client_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr CancelSpinActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr CancelSpinActionTestFixture::node_ = nullptr; std::shared_ptr CancelSpinActionTestFixture::action_server_ = nullptr; -std::shared_ptr> +std::shared_ptr> CancelSpinActionTestFixture::client_ = nullptr; BT::NodeConfiguration * CancelSpinActionTestFixture::config_ = nullptr; @@ -127,7 +127,7 @@ TEST_F(CancelSpinActionTestFixture, test_ports) )"; tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); // Creating a dummy goal_msg auto goal_msg = nav2_msgs::action::Spin::Goal(); diff --git a/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp b/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp index 56b1b4b0567..39e12e57650 100644 --- a/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_truncate_path_action.cpp @@ -37,7 +37,7 @@ class TruncatePathTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("change_goal_test_fixture"); + node_ = std::make_shared("change_goal_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -74,13 +74,13 @@ class TruncatePathTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr TruncatePathTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr TruncatePathTestFixture::node_ = nullptr; BT::NodeConfiguration * TruncatePathTestFixture::config_ = nullptr; std::shared_ptr TruncatePathTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp b/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp index f99e48f9287..7dd8d8303e2 100644 --- a/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_wait_action.cpp @@ -42,7 +42,7 @@ class WaitActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("wait_action_test_fixture"); + node_ = std::make_shared("wait_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -97,13 +97,13 @@ class WaitActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr WaitActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr WaitActionTestFixture::node_ = nullptr; std::shared_ptr WaitActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * WaitActionTestFixture::config_ = nullptr; std::shared_ptr WaitActionTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/action/test_wait_cancel_node.cpp b/nav2_behavior_tree/test/plugins/action/test_wait_cancel_node.cpp index e9234cc3347..1ad8d2a83cf 100644 --- a/nav2_behavior_tree/test/plugins/action/test_wait_cancel_node.cpp +++ b/nav2_behavior_tree/test/plugins/action/test_wait_cancel_node.cpp @@ -47,7 +47,7 @@ class CancelWaitActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("cancel_wait_action_test_fixture"); + node_ = std::make_shared("cancel_wait_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -96,19 +96,19 @@ class CancelWaitActionTestFixture : public ::testing::Test } static std::shared_ptr action_server_; - static std::shared_ptr> client_; + static std::shared_ptr> client_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr CancelWaitActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr CancelWaitActionTestFixture::node_ = nullptr; std::shared_ptr CancelWaitActionTestFixture::action_server_ = nullptr; -std::shared_ptr> +std::shared_ptr> CancelWaitActionTestFixture::client_ = nullptr; BT::NodeConfiguration * CancelWaitActionTestFixture::config_ = nullptr; @@ -127,7 +127,7 @@ TEST_F(CancelWaitActionTestFixture, test_ports) )"; tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); // Creating a dummy goal_msg auto goal_msg = nav2_msgs::action::Wait::Goal(); diff --git a/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp b/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp index 8cd761aadf1..18aaf99f8ec 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_is_battery_charging.cpp @@ -28,7 +28,7 @@ class IsBatteryChargingConditionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_is_battery_charging"); + node_ = std::make_shared("test_is_battery_charging"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -45,6 +45,7 @@ class IsBatteryChargingConditionTestFixture : public ::testing::Test battery_pub_ = node_->create_publisher( "/battery_status", rclcpp::SystemDefaultsQoS()); + battery_pub_->on_activate(); } static void TearDownTestCase() @@ -57,16 +58,17 @@ class IsBatteryChargingConditionTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; - static rclcpp::Publisher::SharedPtr battery_pub_; + static nav2::Publisher::SharedPtr + battery_pub_; }; -rclcpp::Node::SharedPtr IsBatteryChargingConditionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr IsBatteryChargingConditionTestFixture::node_ = nullptr; BT::NodeConfiguration * IsBatteryChargingConditionTestFixture::config_ = nullptr; std::shared_ptr IsBatteryChargingConditionTestFixture::factory_ = nullptr; -rclcpp::Publisher::SharedPtr +nav2::Publisher::SharedPtr IsBatteryChargingConditionTestFixture::battery_pub_ = nullptr; TEST_F(IsBatteryChargingConditionTestFixture, test_behavior_power_supply_status) @@ -85,32 +87,32 @@ TEST_F(IsBatteryChargingConditionTestFixture, test_behavior_power_supply_status) battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_CHARGING; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS); battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_DISCHARGING; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_NOT_CHARGING; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); battery_msg.power_supply_status = sensor_msgs::msg::BatteryState::POWER_SUPPLY_STATUS_FULL; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); } diff --git a/nav2_behavior_tree/test/plugins/condition/test_is_battery_low.cpp b/nav2_behavior_tree/test/plugins/condition/test_is_battery_low.cpp index 5e763f56d42..0af03b9afaa 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_is_battery_low.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_is_battery_low.cpp @@ -29,7 +29,7 @@ class IsBatteryLowConditionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_is_battery_low"); + node_ = std::make_shared("test_is_battery_low"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -46,6 +46,7 @@ class IsBatteryLowConditionTestFixture : public ::testing::Test battery_pub_ = node_->create_publisher( "/battery_status", rclcpp::SystemDefaultsQoS()); + battery_pub_->on_activate(); } static void TearDownTestCase() @@ -58,16 +59,17 @@ class IsBatteryLowConditionTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; - static rclcpp::Publisher::SharedPtr battery_pub_; + static nav2::Publisher::SharedPtr + battery_pub_; }; -rclcpp::Node::SharedPtr IsBatteryLowConditionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr IsBatteryLowConditionTestFixture::node_ = nullptr; BT::NodeConfiguration * IsBatteryLowConditionTestFixture::config_ = nullptr; std::shared_ptr IsBatteryLowConditionTestFixture::factory_ = nullptr; -rclcpp::Publisher::SharedPtr +nav2::Publisher::SharedPtr IsBatteryLowConditionTestFixture::battery_pub_ = nullptr; TEST_F(IsBatteryLowConditionTestFixture, test_behavior_percentage) @@ -86,25 +88,25 @@ TEST_F(IsBatteryLowConditionTestFixture, test_behavior_percentage) battery_msg.percentage = 1.0; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); battery_msg.percentage = 0.49; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS); battery_msg.percentage = 0.51; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); battery_msg.percentage = 0.0; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS); } @@ -124,25 +126,25 @@ TEST_F(IsBatteryLowConditionTestFixture, test_behavior_voltage) battery_msg.voltage = 10.0; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); battery_msg.voltage = 4.9; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS); battery_msg.voltage = 5.1; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE); battery_msg.voltage = 0.0; battery_pub_->publish(battery_msg); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(node_); + rclcpp::spin_some(node_->get_node_base_interface()); EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS); } diff --git a/nav2_behavior_tree/test/plugins/condition/test_is_path_valid.cpp b/nav2_behavior_tree/test/plugins/condition/test_is_path_valid.cpp index df973cb280a..fd6febbcc26 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_is_path_valid.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_is_path_valid.cpp @@ -52,7 +52,7 @@ class IsPathValidTestFixture : public ::testing::Test public: void SetUp() { - node_ = std::make_shared("test_is_path_valid_condition"); + node_ = std::make_shared("test_is_path_valid_condition"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); config_->blackboard = BT::Blackboard::create(); @@ -76,14 +76,14 @@ class IsPathValidTestFixture : public ::testing::Test static std::shared_ptr server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; std::shared_ptr IsPathValidTestFixture::server_ = nullptr; -rclcpp::Node::SharedPtr IsPathValidTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr IsPathValidTestFixture::node_ = nullptr; BT::NodeConfiguration * IsPathValidTestFixture::config_ = nullptr; std::shared_ptr IsPathValidTestFixture::factory_ = nullptr; std::shared_ptr IsPathValidTestFixture::tree_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/condition/test_is_stopped.cpp b/nav2_behavior_tree/test/plugins/condition/test_is_stopped.cpp index 26ae239a180..c4c0d173ac2 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_is_stopped.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_is_stopped.cpp @@ -61,6 +61,7 @@ TEST_F(IsStoppedTestFixture, test_behavior) { auto odom_pub = node_->create_publisher("odom", rclcpp::SystemDefaultsQoS()); + odom_pub->on_activate(); nav_msgs::msg::Odometry odom_msg; // Test FAILURE when robot is moving diff --git a/nav2_behavior_tree/test/plugins/condition/test_is_stuck.cpp b/nav2_behavior_tree/test/plugins/condition/test_is_stuck.cpp index 6fc54a35cd4..22b14ce3e19 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_is_stuck.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_is_stuck.cpp @@ -50,7 +50,8 @@ IsStuckTestFixture::bt_node_ = nullptr; TEST_F(IsStuckTestFixture, test_behavior) { - auto odom_pub = node_->create_publisher("odom", 1); + auto odom_pub = node_->create_publisher("odom"); + odom_pub->on_activate(); nav_msgs::msg::Odometry odom_msg; // fill up odometry history with zero velocity diff --git a/nav2_behavior_tree/test/plugins/condition/test_path_expiring_timer.cpp b/nav2_behavior_tree/test/plugins/condition/test_path_expiring_timer.cpp index e21ce307da8..73c71569afc 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_path_expiring_timer.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_path_expiring_timer.cpp @@ -32,7 +32,7 @@ class PathExpiringTimerConditionTestFixture : public nav2_behavior_tree::Behavio public: void SetUp() { - node_ = std::make_shared("test_path_expiring_condition"); + node_ = std::make_shared("test_path_expiring_condition"); config_ = new BT::NodeConfiguration(); config_->input_ports["seconds"] = 1.0; config_->input_ports["path"] = ""; @@ -52,12 +52,12 @@ class PathExpiringTimerConditionTestFixture : public nav2_behavior_tree::Behavio } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static std::shared_ptr bt_node_; static BT::NodeConfiguration * config_; }; -rclcpp::Node::SharedPtr PathExpiringTimerConditionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr PathExpiringTimerConditionTestFixture::node_ = nullptr; std::shared_ptr PathExpiringTimerConditionTestFixture::bt_node_ = nullptr; BT::NodeConfiguration * PathExpiringTimerConditionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp b/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp index 73316dfa63f..e01d5439ab2 100644 --- a/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp +++ b/nav2_behavior_tree/test/plugins/condition/test_transform_available.cpp @@ -27,7 +27,7 @@ class TransformAvailableConditionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_behavior_tree_fixture"); + node_ = std::make_shared("test_behavior_tree_fixture"); transform_handler_ = std::make_shared(node_); factory_ = std::make_shared(); @@ -82,14 +82,14 @@ class TransformAvailableConditionTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static std::shared_ptr transform_handler_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr TransformAvailableConditionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr TransformAvailableConditionTestFixture::node_ = nullptr; std::shared_ptr TransformAvailableConditionTestFixture::transform_handler_ = nullptr; BT::NodeConfiguration * TransformAvailableConditionTestFixture::config_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/decorator/test_goal_updater_node.cpp b/nav2_behavior_tree/test/plugins/decorator/test_goal_updater_node.cpp index fa9cc46ab24..1766dfbd418 100644 --- a/nav2_behavior_tree/test/plugins/decorator/test_goal_updater_node.cpp +++ b/nav2_behavior_tree/test/plugins/decorator/test_goal_updater_node.cpp @@ -32,7 +32,7 @@ class GoalUpdaterTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("goal_updater_test_fixture"); + node_ = std::make_shared("goal_updater_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -69,13 +69,13 @@ class GoalUpdaterTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr GoalUpdaterTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr GoalUpdaterTestFixture::node_ = nullptr; BT::NodeConfiguration * GoalUpdaterTestFixture::config_ = nullptr; std::shared_ptr GoalUpdaterTestFixture::factory_ = nullptr; @@ -129,8 +129,10 @@ TEST_F(GoalUpdaterTestFixture, test_older_goal_update) tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); auto goal_updater_pub = node_->create_publisher("goal_update", 10); + goal_updater_pub->on_activate(); auto goals_updater_pub = node_->create_publisher("goals_update", 10); + goals_updater_pub->on_activate(); // create new goal and set it on blackboard geometry_msgs::msg::PoseStamped goal; @@ -180,8 +182,10 @@ TEST_F(GoalUpdaterTestFixture, test_get_latest_goal_update) tree_ = std::make_shared(factory_->createTreeFromText(xml_txt, config_->blackboard)); auto goal_updater_pub = node_->create_publisher("goal_update", 10); + goal_updater_pub->on_activate(); auto goals_updater_pub = node_->create_publisher("goals_update", 10); + goals_updater_pub->on_activate(); // create new goal and set it on blackboard geometry_msgs::msg::PoseStamped goal; diff --git a/nav2_behavior_tree/test/plugins/decorator/test_path_longer_on_approach.cpp b/nav2_behavior_tree/test/plugins/decorator/test_path_longer_on_approach.cpp index 5d521e205c1..816655d91bd 100644 --- a/nav2_behavior_tree/test/plugins/decorator/test_path_longer_on_approach.cpp +++ b/nav2_behavior_tree/test/plugins/decorator/test_path_longer_on_approach.cpp @@ -34,7 +34,7 @@ class PathLongerOnApproachTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("path_longer_on_approach_test_fixture"); + node_ = std::make_shared("path_longer_on_approach_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -71,13 +71,13 @@ class PathLongerOnApproachTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr PathLongerOnApproachTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr PathLongerOnApproachTestFixture::node_ = nullptr; BT::NodeConfiguration * PathLongerOnApproachTestFixture::config_ = nullptr; std::shared_ptr PathLongerOnApproachTestFixture::factory_ = nullptr; diff --git a/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp b/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp index 45b35f00daf..819e3465cb1 100644 --- a/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp +++ b/nav2_behavior_tree/test/plugins/decorator/test_speed_controller.cpp @@ -86,7 +86,8 @@ SpeedControllerTestFixture::dummy_node_ = nullptr; */ TEST_F(SpeedControllerTestFixture, test_behavior) { - auto odom_pub = node_->create_publisher("odom", 1); + auto odom_pub = node_->create_publisher("odom"); + odom_pub->on_activate(); nav_msgs::msg::Odometry odom_msg; auto time = node_->now(); diff --git a/nav2_behavior_tree/test/test_bt_utils.cpp b/nav2_behavior_tree/test/test_bt_utils.cpp index d1deeab3bbd..97d038d2aa8 100644 --- a/nav2_behavior_tree/test/test_bt_utils.cpp +++ b/nav2_behavior_tree/test/test_bt_utils.cpp @@ -559,7 +559,7 @@ TEST(deconflictPortAndParamFrameTest, test_correct_syntax) auto tree = factory.createTreeFromText(xml_txt); rclcpp::init(0, nullptr); - std::shared_ptr node = std::make_shared("test_node"); + nav2::LifecycleNode::SharedPtr node = std::make_shared("test_node"); node->declare_parameter("test", 2); node->declare_parameter("test_alternative", 3); diff --git a/nav2_behavior_tree/test/utils/test_behavior_tree_fixture.hpp b/nav2_behavior_tree/test/utils/test_behavior_tree_fixture.hpp index 7bf08ddd440..48167d1b4a8 100644 --- a/nav2_behavior_tree/test/utils/test_behavior_tree_fixture.hpp +++ b/nav2_behavior_tree/test/utils/test_behavior_tree_fixture.hpp @@ -22,6 +22,8 @@ #include "behaviortree_cpp/bt_factory.h" #include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "test_transform_handler.hpp" #include "test_dummy_tree_node.hpp" @@ -34,7 +36,12 @@ class BehaviorTreeTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("test_behavior_tree_fixture"); + node_ = std::make_shared("test_behavior_tree_fixture"); + + // Configure and activate the lifecycle node + node_->configure(); + node_->activate(); + transform_handler_ = std::make_shared(node_); factory_ = std::make_shared(); @@ -64,6 +71,11 @@ class BehaviorTreeTestFixture : public ::testing::Test static void TearDownTestCase() { transform_handler_->deactivate(); + + // Properly deactivate and cleanup the lifecycle node + node_->deactivate(); + node_->cleanup(); + delete config_; config_ = nullptr; transform_handler_.reset(); @@ -72,7 +84,7 @@ class BehaviorTreeTestFixture : public ::testing::Test } protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static std::shared_ptr transform_handler_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; @@ -80,7 +92,7 @@ class BehaviorTreeTestFixture : public ::testing::Test } // namespace nav2_behavior_tree -rclcpp::Node::SharedPtr nav2_behavior_tree::BehaviorTreeTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr nav2_behavior_tree::BehaviorTreeTestFixture::node_ = nullptr; std::shared_ptr nav2_behavior_tree::BehaviorTreeTestFixture::transform_handler_ = nullptr; diff --git a/nav2_behavior_tree/test/utils/test_transform_handler.hpp b/nav2_behavior_tree/test/utils/test_transform_handler.hpp index 7f12d3167e0..19cfcdfa222 100644 --- a/nav2_behavior_tree/test/utils/test_transform_handler.hpp +++ b/nav2_behavior_tree/test/utils/test_transform_handler.hpp @@ -24,7 +24,8 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_action.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" #include "tf2_msgs/msg/tf_message.hpp" @@ -40,7 +41,7 @@ namespace nav2_behavior_tree class TransformHandler { public: - explicit TransformHandler(rclcpp::Node::SharedPtr & node) + explicit TransformHandler(nav2::LifecycleNode::SharedPtr & node) : node_(node), is_active_(false), base_transform_(nullptr), @@ -66,7 +67,7 @@ class TransformHandler is_active_ = true; // Launch a thread to process the messages for this node - spin_thread_ = std::make_unique(node_->get_node_base_interface()); + spin_thread_ = std::make_unique(node_->get_node_base_interface()); startRobotTransform(); } @@ -143,12 +144,12 @@ class TransformHandler 100ms, std::bind(&TransformHandler::publishRobotTransform, this)); } - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; bool is_active_; // A thread for spinning the ROS node - std::unique_ptr spin_thread_; + std::unique_ptr spin_thread_; // Subscriber diff --git a/nav2_behaviors/CMakeLists.txt b/nav2_behaviors/CMakeLists.txt index d1085c038a8..2e67a685f3a 100644 --- a/nav2_behaviors/CMakeLists.txt +++ b/nav2_behaviors/CMakeLists.txt @@ -16,6 +16,7 @@ find_package(std_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -30,6 +31,7 @@ target_include_directories(nav2_spin_behavior PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_spin_behavior PUBLIC ${geometry_msgs_TARGETS} @@ -55,6 +57,7 @@ target_include_directories(nav2_wait_behavior PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_wait_behavior PUBLIC ${geometry_msgs_TARGETS} @@ -75,6 +78,7 @@ target_include_directories(nav2_drive_on_heading_behavior PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_drive_on_heading_behavior PUBLIC ${geometry_msgs_TARGETS} @@ -98,6 +102,7 @@ target_include_directories(nav2_back_up_behavior PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_back_up_behavior PUBLIC ${geometry_msgs_TARGETS} @@ -121,6 +126,7 @@ target_include_directories(nav2_assisted_teleop_behavior PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_assisted_teleop_behavior PUBLIC ${geometry_msgs_TARGETS} @@ -148,6 +154,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC nav2_core::nav2_core @@ -228,8 +235,10 @@ ament_export_dependencies( rclcpp rclcpp_lifecycle std_msgs + nav2_ros_common tf2 tf2_ros + nav2_ros_common ) ament_export_targets(${library_name}) ament_package() diff --git a/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp b/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp index a791d6324f4..7301cef3836 100644 --- a/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp +++ b/nav2_behaviors/include/nav2_behaviors/behavior_server.hpp @@ -18,7 +18,7 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/transform_listener.h" #include "tf2_ros/create_timer_ros.h" #include "pluginlib/class_loader.hpp" @@ -35,7 +35,7 @@ namespace behavior_server * @class behavior_server::BehaviorServer * @brief An server hosting a map of behavior plugins */ -class BehaviorServer : public nav2_util::LifecycleNode +class BehaviorServer : public nav2::LifecycleNode { public: /** @@ -64,27 +64,27 @@ class BehaviorServer : public nav2_util::LifecycleNode /** * @brief Configure lifecycle server */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activate lifecycle server */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivate lifecycle server */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Cleanup lifecycle server */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Shutdown lifecycle server */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; std::shared_ptr tf_; std::shared_ptr transform_listener_; diff --git a/nav2_behaviors/include/nav2_behaviors/plugins/assisted_teleop.hpp b/nav2_behaviors/include/nav2_behaviors/plugins/assisted_teleop.hpp index 772bb894a09..057d09c9bfe 100644 --- a/nav2_behaviors/include/nav2_behaviors/plugins/assisted_teleop.hpp +++ b/nav2_behaviors/include/nav2_behaviors/plugins/assisted_teleop.hpp @@ -100,7 +100,7 @@ class AssistedTeleop : public TimedBehavior // subscribers std::unique_ptr vel_sub_; - rclcpp::Subscription::SharedPtr preempt_teleop_sub_; + nav2::Subscription::SharedPtr preempt_teleop_sub_; rclcpp::Duration command_time_allowance_{0, 0}; rclcpp::Time end_time_; diff --git a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp index 102b61a0d16..b903c965784 100644 --- a/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp +++ b/nav2_behaviors/include/nav2_behaviors/plugins/drive_on_heading.hpp @@ -25,7 +25,7 @@ #include "nav2_behaviors/timed_behavior.hpp" #include "nav2_msgs/action/drive_on_heading.hpp" #include "nav2_msgs/action/back_up.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" namespace nav2_behaviors @@ -248,18 +248,18 @@ class DriveOnHeading : public TimedBehavior throw std::runtime_error{"Failed to lock node"}; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "simulate_ahead_time", rclcpp::ParameterValue(2.0)); node->get_parameter("simulate_ahead_time", simulate_ahead_time_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, this->behavior_name_ + ".acceleration_limit", rclcpp::ParameterValue(2.5)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, this->behavior_name_ + ".deceleration_limit", rclcpp::ParameterValue(-2.5)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, this->behavior_name_ + ".minimum_speed", rclcpp::ParameterValue(0.10)); node->get_parameter(this->behavior_name_ + ".acceleration_limit", acceleration_limit_); diff --git a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp index d0ad026a4f3..70d0f30fa30 100644 --- a/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp +++ b/nav2_behaviors/include/nav2_behaviors/timed_behavior.hpp @@ -31,7 +31,7 @@ #include "geometry_msgs/msg/twist.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_util/twist_publisher.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/simple_action_server.hpp" #include "nav2_core/behavior.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" @@ -66,7 +66,7 @@ template class TimedBehavior : public nav2_core::Behavior { public: - using ActionServer = nav2_util::SimpleActionServer; + using ActionServer = nav2::SimpleActionServer; /** * @brief A TimedBehavior constructor @@ -113,7 +113,7 @@ class TimedBehavior : public nav2_core::Behavior // configure the server on lifecycle setup void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf, std::shared_ptr local_collision_checker, std::shared_ptr global_collision_checker) @@ -135,15 +135,15 @@ class TimedBehavior : public nav2_core::Behavior node->get_parameter("robot_base_frame", robot_base_frame_); node->get_parameter("transform_tolerance", transform_tolerance_); - action_server_ = std::make_shared( - node, behavior_name_, + action_server_ = node->create_action_server( + behavior_name_, std::bind(&TimedBehavior::execute, this), nullptr, std::chrono::milliseconds( 500), false); local_collision_checker_ = local_collision_checker; global_collision_checker_ = global_collision_checker; - vel_pub_ = std::make_unique(node, "cmd_vel", 1); + vel_pub_ = std::make_unique(node, "cmd_vel"); onConfigure(); } @@ -175,11 +175,11 @@ class TimedBehavior : public nav2_core::Behavior } protected: - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; std::string behavior_name_; std::unique_ptr vel_pub_; - std::shared_ptr action_server_; + typename ActionServer::SharedPtr action_server_; std::shared_ptr local_collision_checker_; std::shared_ptr global_collision_checker_; std::shared_ptr tf_; diff --git a/nav2_behaviors/package.xml b/nav2_behaviors/package.xml index 5c983cb3554..c3739a3461e 100644 --- a/nav2_behaviors/package.xml +++ b/nav2_behaviors/package.xml @@ -24,6 +24,7 @@ tf2 tf2_geometry_msgs tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_behaviors/plugins/assisted_teleop.cpp b/nav2_behaviors/plugins/assisted_teleop.cpp index 319d909fc3d..95dbb3fd145 100644 --- a/nav2_behaviors/plugins/assisted_teleop.cpp +++ b/nav2_behaviors/plugins/assisted_teleop.cpp @@ -15,7 +15,7 @@ #include #include "nav2_behaviors/plugins/assisted_teleop.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_behaviors { @@ -32,15 +32,15 @@ void AssistedTeleop::onConfigure() } // set up parameters - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "projection_time", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "simulation_time_step", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "cmd_vel_teleop", rclcpp::ParameterValue(std::string("cmd_vel_teleop"))); @@ -52,7 +52,7 @@ void AssistedTeleop::onConfigure() vel_sub_ = std::make_unique( node, - cmd_vel_teleop, rclcpp::SystemDefaultsQoS(), + cmd_vel_teleop, [&](geometry_msgs::msg::Twist::SharedPtr msg) { teleop_twist_.twist = *msg; }, [&](geometry_msgs::msg::TwistStamped::SharedPtr msg) { @@ -60,7 +60,7 @@ void AssistedTeleop::onConfigure() }); preempt_teleop_sub_ = node->create_subscription( - "preempt_teleop", rclcpp::SystemDefaultsQoS(), + "preempt_teleop", std::bind( &AssistedTeleop::preemptTeleopCallback, this, std::placeholders::_1)); diff --git a/nav2_behaviors/plugins/spin.cpp b/nav2_behaviors/plugins/spin.cpp index 345268ab8ec..ece15c81359 100644 --- a/nav2_behaviors/plugins/spin.cpp +++ b/nav2_behaviors/plugins/spin.cpp @@ -21,7 +21,7 @@ #include "nav2_behaviors/plugins/spin.hpp" #include "tf2/utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" using namespace std::chrono_literals; @@ -50,22 +50,22 @@ void Spin::onConfigure() throw std::runtime_error{"Failed to lock node"}; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "simulate_ahead_time", rclcpp::ParameterValue(2.0)); node->get_parameter("simulate_ahead_time", simulate_ahead_time_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "max_rotational_vel", rclcpp::ParameterValue(1.0)); node->get_parameter("max_rotational_vel", max_rotational_vel_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "min_rotational_vel", rclcpp::ParameterValue(0.4)); node->get_parameter("min_rotational_vel", min_rotational_vel_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "rotational_acc_lim", rclcpp::ParameterValue(3.2)); node->get_parameter("rotational_acc_lim", rotational_acc_lim_); diff --git a/nav2_behaviors/src/behavior_server.cpp b/nav2_behaviors/src/behavior_server.cpp index a04aea40315..54ace7bac0a 100644 --- a/nav2_behaviors/src/behavior_server.cpp +++ b/nav2_behaviors/src/behavior_server.cpp @@ -16,7 +16,7 @@ #include #include #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_behaviors/behavior_server.hpp" namespace behavior_server @@ -77,7 +77,7 @@ BehaviorServer::~BehaviorServer() behaviors_.clear(); } -nav2_util::CallbackReturn +nav2::CallbackReturn BehaviorServer::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -92,12 +92,12 @@ BehaviorServer::on_configure(const rclcpp_lifecycle::State & state) behavior_types_.resize(behavior_ids_.size()); if (!loadBehaviorPlugins()) { on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } setupResourcesForBehaviorPlugins(); configureBehaviorPlugins(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool @@ -107,7 +107,7 @@ BehaviorServer::loadBehaviorPlugins() for (size_t i = 0; i != behavior_ids_.size(); i++) { try { - behavior_types_[i] = nav2_util::get_plugin_type_param(node, behavior_ids_[i]); + behavior_types_[i] = nav2::get_plugin_type_param(node, behavior_ids_[i]); RCLCPP_INFO( get_logger(), "Creating behavior plugin %s of type %s", behavior_ids_[i].c_str(), behavior_types_[i].c_str()); @@ -191,7 +191,7 @@ void BehaviorServer::setupResourcesForBehaviorPlugins() } } -nav2_util::CallbackReturn +nav2::CallbackReturn BehaviorServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -203,10 +203,10 @@ BehaviorServer::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn BehaviorServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -219,10 +219,10 @@ BehaviorServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn BehaviorServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -245,14 +245,14 @@ BehaviorServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) local_collision_checker_.reset(); global_collision_checker_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn BehaviorServer::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } } // end namespace behavior_server diff --git a/nav2_behaviors/test/test_behaviors.cpp b/nav2_behaviors/test/test_behaviors.cpp index ac76d82dea1..35df094b5f5 100644 --- a/nav2_behaviors/test/test_behaviors.cpp +++ b/nav2_behaviors/test/test_behaviors.cpp @@ -109,7 +109,7 @@ class BehaviorTest : public ::testing::Test void SetUp() override { node_lifecycle_ = - std::make_shared( + std::make_shared( "LifecycleBehaviorTestNode", rclcpp::NodeOptions()); node_lifecycle_->declare_parameter( "local_costmap_topic", @@ -233,9 +233,9 @@ class BehaviorTest : public ::testing::Test return future_result.get(); } - std::shared_ptr node_lifecycle_; + nav2::LifecycleNode::SharedPtr node_lifecycle_; std::shared_ptr behavior_; - std::shared_ptr> client_; + std::shared_ptr> client_; std::shared_ptr> goal_handle_; std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; diff --git a/nav2_bt_navigator/CMakeLists.txt b/nav2_bt_navigator/CMakeLists.txt index 5ced439631c..c5cdd898d24 100644 --- a/nav2_bt_navigator/CMakeLists.txt +++ b/nav2_bt_navigator/CMakeLists.txt @@ -16,6 +16,7 @@ find_package(rclcpp_action REQUIRED) find_package(rclcpp_components REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -30,6 +31,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC nav2_core::nav2_core @@ -52,6 +54,7 @@ target_include_directories(${executable_name} PRIVATE "$" "$" + "$" ) target_link_libraries(${executable_name} PRIVATE ${library_name} @@ -63,6 +66,7 @@ target_include_directories(nav2_navigate_to_pose_navigator PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_navigate_to_pose_navigator PUBLIC ${geometry_msgs_TARGETS} @@ -85,6 +89,7 @@ target_include_directories(nav2_navigate_through_poses PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_navigate_through_poses PUBLIC ${geometry_msgs_TARGETS} @@ -128,6 +133,6 @@ endif() ament_export_include_directories(include/${PROJECT_NAME}) ament_export_libraries(${library_name} nav2_navigate_to_pose_navigator nav2_navigate_through_poses) -ament_export_dependencies(geometry_msgs nav2_core nav2_msgs nav2_util nav_msgs pluginlib rclcpp rclcpp_action tf2_ros) +ament_export_dependencies(geometry_msgs nav2_core nav2_msgs nav2_util nav2_ros_common nav_msgs pluginlib rclcpp rclcpp_action tf2_ros) ament_export_targets(export_${library_name}) ament_package() 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 6e77f37f671..8a25e5a2c8d 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp @@ -20,7 +20,7 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/odometry_utils.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "tf2_ros/buffer.h" @@ -37,7 +37,7 @@ namespace nav2_bt_navigator * @brief An action server that uses behavior tree for navigating a robot to its * goal position. */ -class BtNavigator : public nav2_util::LifecycleNode +class BtNavigator : public nav2::LifecycleNode { public: /** @@ -59,31 +59,31 @@ class BtNavigator : public nav2_util::LifecycleNode * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activates action server * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivates action server * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Resets member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in shutdown state * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; // To handle all the BT related execution pluginlib::ClassLoader class_loader_; diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp index 2226c5fc3d7..427373ded47 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_through_poses.hpp @@ -53,7 +53,7 @@ class NavigateThroughPosesNavigator * @param odom_smoother Object to get current smoothed robot's speed */ bool configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr node, + nav2::LifecycleNode::WeakPtr node, std::shared_ptr odom_smoother) override; /** @@ -67,7 +67,7 @@ class NavigateThroughPosesNavigator * @param node WeakPtr to the lifecycle node * @return string Filepath to default XML */ - std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) override; + std::string getDefaultBTFilepath(nav2::LifecycleNode::WeakPtr node) override; protected: /** diff --git a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp index 447d02cc449..9b9290095a7 100644 --- a/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp +++ b/nav2_bt_navigator/include/nav2_bt_navigator/navigators/navigate_to_pose.hpp @@ -53,7 +53,7 @@ class NavigateToPoseNavigator * @param odom_smoother Object to get current smoothed robot's speed */ bool configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr node, + nav2::LifecycleNode::WeakPtr node, std::shared_ptr odom_smoother) override; /** @@ -79,7 +79,7 @@ class NavigateToPoseNavigator * @param node WeakPtr to the lifecycle node * @return string Filepath to default XML */ - std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) override; + std::string getDefaultBTFilepath(nav2::LifecycleNode::WeakPtr node) override; protected: /** @@ -122,8 +122,8 @@ class NavigateToPoseNavigator rclcpp::Time start_time_; - rclcpp::Subscription::SharedPtr goal_sub_; - rclcpp_action::Client::SharedPtr self_client_; + nav2::Subscription::SharedPtr goal_sub_; + nav2::ActionClient::SharedPtr self_client_; std::string goal_blackboard_id_; std::string path_blackboard_id_; diff --git a/nav2_bt_navigator/package.xml b/nav2_bt_navigator/package.xml index d7a8e903bc3..825e8f9eec3 100644 --- a/nav2_bt_navigator/package.xml +++ b/nav2_bt_navigator/package.xml @@ -23,6 +23,7 @@ rclcpp_components rclcpp_lifecycle tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp index 12047c2feef..a3e95776b72 100644 --- a/nav2_bt_navigator/src/bt_navigator.cpp +++ b/nav2_bt_navigator/src/bt_navigator.cpp @@ -20,20 +20,20 @@ #include #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/string_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_behavior_tree/bt_utils.hpp" #include "nav2_behavior_tree/plugins_list.hpp" -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; namespace nav2_bt_navigator { BtNavigator::BtNavigator(rclcpp::NodeOptions options) -: nav2_util::LifecycleNode("bt_navigator", "", +: nav2::LifecycleNode("bt_navigator", "", options.automatically_declare_parameters_from_overrides(true)), class_loader_("nav2_core", "nav2_core::NavigatorBase") { @@ -57,7 +57,7 @@ BtNavigator::~BtNavigator() { } -nav2_util::CallbackReturn +nav2::CallbackReturn BtNavigator::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -121,7 +121,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state) // Load navigator plugins for (size_t i = 0; i != navigator_ids.size(); i++) { try { - std::string navigator_type = nav2_util::get_plugin_type_param(node, navigator_ids[i]); + std::string navigator_type = nav2::get_plugin_type_param(node, navigator_ids[i]); RCLCPP_INFO( get_logger(), "Creating navigator id %s of type %s", navigator_ids[i].c_str(), navigator_type.c_str()); @@ -130,54 +130,54 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & state) node, plugin_lib_names, feedback_utils, &plugin_muxer_, odom_smoother_)) { - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } catch (const std::exception & ex) { RCLCPP_FATAL( get_logger(), "Failed to create navigator id %s." " Exception: %s", navigator_ids[i].c_str(), ex.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn BtNavigator::on_activate(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Activating"); for (size_t i = 0; i != navigators_.size(); i++) { if (!navigators_[i]->on_activate()) { on_deactivate(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn BtNavigator::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); for (size_t i = 0; i != navigators_.size(); i++) { if (!navigators_[i]->on_deactivate()) { - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn BtNavigator::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -188,20 +188,20 @@ BtNavigator::on_cleanup(const rclcpp_lifecycle::State & /*state*/) for (size_t i = 0; i != navigators_.size(); i++) { if (!navigators_[i]->on_cleanup()) { - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } navigators_.clear(); RCLCPP_INFO(get_logger(), "Completed Cleaning up"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn BtNavigator::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } } // namespace nav2_bt_navigator diff --git a/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp b/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp index a28e1c59586..4dfd57a3eef 100644 --- a/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp +++ b/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp @@ -24,7 +24,7 @@ namespace nav2_bt_navigator bool NavigateThroughPosesNavigator::configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, + nav2::LifecycleNode::WeakPtr parent_node, std::shared_ptr odom_smoother) { start_time_ = rclcpp::Time(0); @@ -69,7 +69,7 @@ NavigateThroughPosesNavigator::configure( std::string NavigateThroughPosesNavigator::getDefaultBTFilepath( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node) + nav2::LifecycleNode::WeakPtr parent_node) { std::string default_bt_xml_filename; auto node = parent_node.lock(); diff --git a/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp b/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp index a421db4c3f6..5d2218000f7 100644 --- a/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp +++ b/nav2_bt_navigator/src/navigators/navigate_to_pose.cpp @@ -23,7 +23,7 @@ namespace nav2_bt_navigator bool NavigateToPoseNavigator::configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, + nav2::LifecycleNode::WeakPtr parent_node, std::shared_ptr odom_smoother) { start_time_ = rclcpp::Time(0); @@ -44,11 +44,10 @@ NavigateToPoseNavigator::configure( // Odometry smoother object for getting current speed odom_smoother_ = odom_smoother; - self_client_ = rclcpp_action::create_client(node, getName()); + self_client_ = node->create_action_client(getName()); goal_sub_ = node->create_subscription( "goal_pose", - rclcpp::SystemDefaultsQoS(), std::bind(&NavigateToPoseNavigator::onGoalPoseReceived, this, std::placeholders::_1)); if (!node->has_parameter(getName() + ".enable_groot_monitoring")) { @@ -68,7 +67,7 @@ NavigateToPoseNavigator::configure( std::string NavigateToPoseNavigator::getDefaultBTFilepath( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node) + nav2::LifecycleNode::WeakPtr parent_node) { std::string default_bt_xml_filename; auto node = parent_node.lock(); diff --git a/nav2_collision_monitor/CMakeLists.txt b/nav2_collision_monitor/CMakeLists.txt index b56fde855c8..21c3c1aabdb 100644 --- a/nav2_collision_monitor/CMakeLists.txt +++ b/nav2_collision_monitor/CMakeLists.txt @@ -15,6 +15,7 @@ find_package(std_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) find_package(visualization_msgs REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -38,7 +39,8 @@ add_library(${monitor_library_name} SHARED target_include_directories(${monitor_library_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${monitor_library_name} PUBLIC ${geometry_msgs_TARGETS} nav2_costmap_2d::nav2_costmap_2d_client @@ -71,7 +73,8 @@ add_library(${detector_library_name} SHARED target_include_directories(${detector_library_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${detector_library_name} PUBLIC ${geometry_msgs_TARGETS} nav2_costmap_2d::nav2_costmap_2d_client @@ -95,7 +98,8 @@ add_executable(${monitor_executable_name} target_include_directories(${monitor_executable_name} PRIVATE "$" - "$") + "$" + "$") target_link_libraries(${monitor_executable_name} PRIVATE rclcpp::rclcpp ${monitor_library_name} @@ -107,7 +111,8 @@ add_executable(${detector_executable_name} target_include_directories(${detector_executable_name} PRIVATE "$" - "$") + "$" + "$") target_link_libraries(${detector_executable_name} PRIVATE rclcpp::rclcpp ${detector_library_name} @@ -161,6 +166,7 @@ ament_export_dependencies( sensor_msgs tf2 tf2_ros + nav2_ros_common visualization_msgs ) ament_export_targets(export_${PROJECT_NAME}) diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp index 2476b17d886..f9eb52e8023 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp @@ -43,7 +43,7 @@ class Circle : public Polygon * @param transform_tolerance Transform tolerance */ Circle( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -115,7 +115,7 @@ class Circle : public Polygon /// @brief (radius * radius) value. Stored for optimization. double radius_squared_ = -1.0; /// @brief Radius subscription - rclcpp::Subscription::SharedPtr radius_sub_; + nav2::Subscription::SharedPtr radius_sub_; }; // class Circle } // namespace nav2_collision_monitor diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp index a3a429b2daa..59b807f562e 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_detector_node.hpp @@ -26,7 +26,7 @@ #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/msg/collision_detector_state.hpp" #include "visualization_msgs/msg/marker_array.hpp" @@ -46,7 +46,7 @@ namespace nav2_collision_monitor /** * @brief Collision Monitor ROS2 node */ -class CollisionDetector : public nav2_util::LifecycleNode +class CollisionDetector : public nav2::LifecycleNode { public: /** @@ -66,31 +66,31 @@ class CollisionDetector : public nav2_util::LifecycleNode * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief: Activates LifecyclePublishers, polygons and main processor, creates bond connection * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief: Resets all subscribers/publishers, polygons/data sources arrays * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called in shutdown state * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; protected: /** @@ -148,10 +148,10 @@ class CollisionDetector : public nav2_util::LifecycleNode std::vector> sources_; /// @brief collision monitor state publisher - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr state_pub_; /// @brief Collision points marker publisher - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr collision_points_marker_pub_; /// @brief timer that runs actions rclcpp::TimerBase::SharedPtr timer_; diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp index 69274b06fdb..d73804cb827 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/collision_monitor_node.hpp @@ -29,7 +29,7 @@ #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/twist_publisher.hpp" #include "nav2_util/twist_subscriber.hpp" #include "nav2_msgs/msg/collision_monitor_state.hpp" @@ -50,7 +50,7 @@ namespace nav2_collision_monitor /** * @brief Collision Monitor ROS2 node */ -class CollisionMonitor : public nav2_util::LifecycleNode +class CollisionMonitor : public nav2::LifecycleNode { public: /** @@ -70,31 +70,31 @@ class CollisionMonitor : public nav2_util::LifecycleNode * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief: Activates LifecyclePublishers, polygons and main processor, creates bond connection * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief: Resets all subscribers/publishers, polygons/data sources arrays * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called in shutdown state * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; protected: /** @@ -220,11 +220,11 @@ class CollisionMonitor : public nav2_util::LifecycleNode std::unique_ptr cmd_vel_out_pub_; /// @brief CollisionMonitor state publisher - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr state_pub_; /// @brief Collision points marker publisher - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr collision_points_marker_pub_; /// @brief Whether main routine is active diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp index ea370f9acca..1d6b6e27f86 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp @@ -45,7 +45,7 @@ class PointCloud : public Source * considering the difference between current time and latest source time */ PointCloud( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -91,7 +91,7 @@ class PointCloud : public Source // ----- Variables ----- /// @brief PointCloud data subscriber - rclcpp::Subscription::SharedPtr data_sub_; + nav2::Subscription::SharedPtr data_sub_; // Minimum and maximum height of PointCloud projected to 2D space double min_height_, max_height_; diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp index 5dff3d7371c..12d64259993 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp @@ -26,7 +26,7 @@ #include "tf2/time.hpp" #include "tf2_ros/buffer.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/footprint_subscriber.hpp" #include "nav2_collision_monitor/types.hpp" @@ -51,7 +51,7 @@ class Polygon * @param transform_tolerance Transform tolerance */ Polygon( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -257,7 +257,7 @@ class Polygon // ----- Variables ----- /// @brief Collision Monitor node - nav2_util::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; /// @brief Collision monitor node logger stored for further usage rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")}; /// @brief Dynamic parameters handler @@ -285,7 +285,7 @@ class Polygon /// @brief Whether the subscription to polygon topic has transient local QoS durability bool polygon_subscribe_transient_local_; /// @brief Polygon subscription - rclcpp::Subscription::SharedPtr polygon_sub_; + nav2::Subscription::SharedPtr polygon_sub_; /// @brief Footprint subscriber std::unique_ptr footprint_sub_; /// @brief Name of the observation sources to check for polygon @@ -307,7 +307,7 @@ class Polygon /// @brief Polygon, used for: 1. visualization; 2. storing latest dynamic polygon message geometry_msgs::msg::PolygonStamped polygon_; /// @brief Polygon publisher for visualization purposes - rclcpp_lifecycle::LifecyclePublisher::SharedPtr polygon_pub_; + nav2::Publisher::SharedPtr polygon_pub_; /// @brief Polygon points (vertices) in a base_frame_id_ std::vector poly_; diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/polygon_source.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/polygon_source.hpp index 8855bb7241e..a25c60030e5 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/polygon_source.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/polygon_source.hpp @@ -46,7 +46,7 @@ class PolygonSource : public Source * considering the difference between current time and latest source time */ PolygonSource( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -101,7 +101,7 @@ class PolygonSource : public Source // ----- Variables ----- /// @brief PolygonSource data subscriber - rclcpp::Subscription::SharedPtr data_sub_; + nav2::Subscription::SharedPtr data_sub_; /// @brief Latest data obtained std::vector data_; diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp index 2bccaac108c..763fe34d451 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/range.hpp @@ -45,7 +45,7 @@ class Range : public Source * considering the difference between current time and latest source time */ Range( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -91,7 +91,7 @@ class Range : public Source // ----- Variables ----- /// @brief Range sensor data subscriber - rclcpp::Subscription::SharedPtr data_sub_; + nav2::Subscription::SharedPtr data_sub_; /// @brief Angle increment (in rad) between two obstacle points at the range arc double obstacles_angle_; diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp index 5c57cdb0148..ed941d19c49 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/scan.hpp @@ -45,7 +45,7 @@ class Scan : public Source * considering the difference between current time and latest source time */ Scan( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -85,7 +85,7 @@ class Scan : public Source // ----- Variables ----- /// @brief Laser scanner data subscriber - rclcpp::Subscription::SharedPtr data_sub_; + nav2::Subscription::SharedPtr data_sub_; /// @brief Latest data obtained from laser scanner sensor_msgs::msg::LaserScan::ConstSharedPtr data_; diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp index 3384bf8d333..312c13ea577 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/source.hpp @@ -25,7 +25,7 @@ #include "tf2_ros/buffer.h" #include "nav2_collision_monitor/types.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "std_msgs/msg/header.hpp" namespace nav2_collision_monitor @@ -50,7 +50,7 @@ class Source * considering the difference between current time and latest source time */ Source( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -141,7 +141,7 @@ class Source // ----- Variables ----- /// @brief Collision Monitor node - nav2_util::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; /// @brief Collision monitor node logger stored for further usage rclcpp::Logger logger_{rclcpp::get_logger("collision_monitor")}; /// @brief Dynamic parameters handler diff --git a/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp b/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp index d93ebd931d2..55f894d87c5 100644 --- a/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp +++ b/nav2_collision_monitor/include/nav2_collision_monitor/velocity_polygon.hpp @@ -22,7 +22,7 @@ #include "geometry_msgs/msg/polygon_stamped.hpp" #include "nav2_collision_monitor/polygon.hpp" #include "nav2_collision_monitor/types.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" #include "tf2_ros/buffer.h" @@ -43,7 +43,7 @@ class VelocityPolygon : public Polygon * @param polygon_name Name of main polygon */ VelocityPolygon( - const nav2_util::LifecycleNode::WeakPtr & node, const std::string & polygon_name, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, const tf2::Duration & transform_tolerance); /** diff --git a/nav2_collision_monitor/package.xml b/nav2_collision_monitor/package.xml index bb166d9bbf4..47ffe9a6d60 100644 --- a/nav2_collision_monitor/package.xml +++ b/nav2_collision_monitor/package.xml @@ -23,6 +23,7 @@ tf2 tf2_ros visualization_msgs + nav2_ros_common ament_cmake_gtest ament_lint_common diff --git a/nav2_collision_monitor/src/circle.cpp b/nav2_collision_monitor/src/circle.cpp index 353db72dc07..c296b2ac660 100644 --- a/nav2_collision_monitor/src/circle.cpp +++ b/nav2_collision_monitor/src/circle.cpp @@ -18,13 +18,13 @@ #include #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_collision_monitor { Circle::Circle( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -95,7 +95,7 @@ bool Circle::getParameters( bool use_dynamic_sub = true; // if getting parameter radius fails, use dynamic subscription try { // Leave it not initialized: the will cause an error if it will not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".radius", rclcpp::PARAMETER_DOUBLE); radius_ = node->get_parameter(polygon_name_ + ".radius").as_double(); radius_squared_ = radius_ * radius_; @@ -138,13 +138,14 @@ void Circle::createSubscription(std::string & polygon_sub_topic) logger_, "[%s]: Subscribing on %s topic for polygon", polygon_name_.c_str(), polygon_sub_topic.c_str()); - rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS(); // set to default + rclcpp::QoS polygon_qos = nav2::qos::StandardTopicQoS(); // set to default if (polygon_subscribe_transient_local_) { polygon_qos.transient_local(); } radius_sub_ = node->create_subscription( - polygon_sub_topic, polygon_qos, - std::bind(&Circle::radiusCallback, this, std::placeholders::_1)); + polygon_sub_topic, + std::bind(&Circle::radiusCallback, this, std::placeholders::_1), + polygon_qos); } } diff --git a/nav2_collision_monitor/src/collision_detector_node.cpp b/nav2_collision_monitor/src/collision_detector_node.cpp index 7f87bc1bb92..739d0d12207 100644 --- a/nav2_collision_monitor/src/collision_detector_node.cpp +++ b/nav2_collision_monitor/src/collision_detector_node.cpp @@ -21,7 +21,7 @@ #include "tf2_ros/create_timer_ros.h" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" using namespace std::chrono_literals; @@ -29,7 +29,7 @@ namespace nav2_collision_monitor { CollisionDetector::CollisionDetector(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("collision_detector", "", options) +: nav2::LifecycleNode("collision_detector", options) { } @@ -39,7 +39,7 @@ CollisionDetector::~CollisionDetector() sources_.clear(); } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionDetector::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -53,21 +53,21 @@ CollisionDetector::on_configure(const rclcpp_lifecycle::State & state) tf_listener_ = std::make_shared(*tf_buffer_); state_pub_ = this->create_publisher( - "collision_detector_state", rclcpp::SystemDefaultsQoS()); + "collision_detector_state"); collision_points_marker_pub_ = this->create_publisher( - "~/collision_points_marker", 1); + "~/collision_points_marker"); // Obtaining ROS parameters if (!getParameters()) { on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionDetector::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -89,10 +89,10 @@ CollisionDetector::on_activate(const rclcpp_lifecycle::State & /*state*/) // Creating bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionDetector::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -112,10 +112,10 @@ CollisionDetector::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // Destroying bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionDetector::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -129,14 +129,14 @@ CollisionDetector::on_cleanup(const rclcpp_lifecycle::State & /*state*/) tf_listener_.reset(); tf_buffer_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionDetector::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool CollisionDetector::getParameters() @@ -147,24 +147,24 @@ bool CollisionDetector::getParameters() auto node = shared_from_this(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "frequency", rclcpp::ParameterValue(10.0)); frequency_ = get_parameter("frequency").as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "base_frame_id", rclcpp::ParameterValue("base_footprint")); base_frame_id = get_parameter("base_frame_id").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "odom_frame_id", rclcpp::ParameterValue("odom")); odom_frame_id = get_parameter("odom_frame_id").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "transform_tolerance", rclcpp::ParameterValue(0.1)); transform_tolerance = tf2::durationFromSec(get_parameter("transform_tolerance").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "source_timeout", rclcpp::ParameterValue(2.0)); source_timeout = rclcpp::Duration::from_seconds(get_parameter("source_timeout").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "base_shift_correction", rclcpp::ParameterValue(true)); const bool base_shift_correction = get_parameter("base_shift_correction").as_bool(); @@ -191,12 +191,12 @@ bool CollisionDetector::configurePolygons( auto node = shared_from_this(); // Leave it to be not initialized: to intentionally cause an error if it will not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "polygons", rclcpp::PARAMETER_STRING_ARRAY); std::vector polygon_names = get_parameter("polygons").as_string_array(); for (std::string polygon_name : polygon_names) { // Leave it not initialized: the will cause an error if it will not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name + ".type", rclcpp::PARAMETER_STRING); const std::string polygon_type = get_parameter(polygon_name + ".type").as_string(); @@ -255,11 +255,11 @@ bool CollisionDetector::configureSources( auto node = shared_from_this(); // Leave it to be not initialized to intentionally cause an error if it will not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY); std::vector source_names = get_parameter("observation_sources").as_string_array(); for (std::string source_name : source_names) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name + ".type", rclcpp::ParameterValue("scan")); // Laser scanner by default const std::string source_type = get_parameter(source_name + ".type").as_string(); diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 420d0268bbf..f85bdf4a866 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -20,7 +20,7 @@ #include "tf2_ros/create_timer_ros.h" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_collision_monitor/kinematics.hpp" @@ -29,7 +29,7 @@ namespace nav2_collision_monitor { CollisionMonitor::CollisionMonitor(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("collision_monitor", "", options), +: nav2::LifecycleNode("collision_monitor", options), process_active_(false), robot_action_prev_{DO_NOTHING, {-1.0, -1.0, -1.0}, ""}, stop_stamp_{0, 0, get_clock()->get_clock_type()}, stop_pub_timeout_(1.0, 0.0) { @@ -41,7 +41,7 @@ CollisionMonitor::~CollisionMonitor() sources_.clear(); } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionMonitor::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -61,45 +61,44 @@ CollisionMonitor::on_configure(const rclcpp_lifecycle::State & state) // Obtaining ROS parameters if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic, state_topic)) { on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } cmd_vel_in_sub_ = std::make_unique( shared_from_this(), cmd_vel_in_topic, - 1, std::bind(&CollisionMonitor::cmdVelInCallbackUnstamped, this, std::placeholders::_1), std::bind(&CollisionMonitor::cmdVelInCallbackStamped, this, std::placeholders::_1)); auto node = shared_from_this(); - cmd_vel_out_pub_ = std::make_unique(node, cmd_vel_out_topic, 1); + cmd_vel_out_pub_ = std::make_unique(node, cmd_vel_out_topic); if (!state_topic.empty()) { state_pub_ = this->create_publisher( - state_topic, 1); + state_topic); } collision_points_marker_pub_ = this->create_publisher( - "~/collision_points_marker", 1); + "~/collision_points_marker"); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "use_realtime_priority", rclcpp::ParameterValue(false)); bool use_realtime_priority = false; node->get_parameter("use_realtime_priority", use_realtime_priority); if (use_realtime_priority) { try { - nav2_util::setSoftRealTimePriority(); + nav2::setSoftRealTimePriority(); } catch (const std::runtime_error & e) { RCLCPP_ERROR(get_logger(), "%s", e.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionMonitor::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -126,10 +125,10 @@ CollisionMonitor::on_activate(const rclcpp_lifecycle::State & /*state*/) // Creating bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionMonitor::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -155,10 +154,10 @@ CollisionMonitor::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // Destroying bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionMonitor::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -174,15 +173,15 @@ CollisionMonitor::on_cleanup(const rclcpp_lifecycle::State & /*state*/) tf_listener_.reset(); tf_buffer_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CollisionMonitor::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } void CollisionMonitor::cmdVelInCallbackStamped(geometry_msgs::msg::TwistStamped::SharedPtr msg) @@ -238,36 +237,36 @@ bool CollisionMonitor::getParameters( auto node = shared_from_this(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_smoothed")); cmd_vel_in_topic = get_parameter("cmd_vel_in_topic").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel")); cmd_vel_out_topic = get_parameter("cmd_vel_out_topic").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "state_topic", rclcpp::ParameterValue("")); state_topic = get_parameter("state_topic").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "base_frame_id", rclcpp::ParameterValue("base_footprint")); base_frame_id = get_parameter("base_frame_id").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "odom_frame_id", rclcpp::ParameterValue("odom")); odom_frame_id = get_parameter("odom_frame_id").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "transform_tolerance", rclcpp::ParameterValue(0.1)); transform_tolerance = tf2::durationFromSec(get_parameter("transform_tolerance").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "source_timeout", rclcpp::ParameterValue(2.0)); source_timeout = rclcpp::Duration::from_seconds(get_parameter("source_timeout").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "base_shift_correction", rclcpp::ParameterValue(true)); const bool base_shift_correction = get_parameter("base_shift_correction").as_bool(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "stop_pub_timeout", rclcpp::ParameterValue(1.0)); stop_pub_timeout_ = rclcpp::Duration::from_seconds(get_parameter("stop_pub_timeout").as_double()); @@ -294,12 +293,12 @@ bool CollisionMonitor::configurePolygons( auto node = shared_from_this(); // Leave it to be not initialized: to intentionally cause an error if it will not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "polygons", rclcpp::PARAMETER_STRING_ARRAY); std::vector polygon_names = get_parameter("polygons").as_string_array(); for (std::string polygon_name : polygon_names) { // Leave it not initialized: the will cause an error if it will not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name + ".type", rclcpp::PARAMETER_STRING); const std::string polygon_type = get_parameter(polygon_name + ".type").as_string(); @@ -347,11 +346,11 @@ bool CollisionMonitor::configureSources( auto node = shared_from_this(); // Leave it to be not initialized: to intentionally cause an error if it will not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY); std::vector source_names = get_parameter("observation_sources").as_string_array(); for (std::string source_name : source_names) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name + ".type", rclcpp::ParameterValue("scan")); // Laser scanner by default const std::string source_type = get_parameter(source_name + ".type").as_string(); diff --git a/nav2_collision_monitor/src/pointcloud.cpp b/nav2_collision_monitor/src/pointcloud.cpp index c54c0524ea0..af584a8e9cc 100644 --- a/nav2_collision_monitor/src/pointcloud.cpp +++ b/nav2_collision_monitor/src/pointcloud.cpp @@ -19,14 +19,14 @@ #include "sensor_msgs/point_cloud2_iterator.hpp" #include "tf2/transform_datatypes.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" namespace nav2_collision_monitor { PointCloud::PointCloud( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -60,10 +60,10 @@ void PointCloud::configure() getParameters(source_topic); - rclcpp::QoS pointcloud_qos = rclcpp::SensorDataQoS(); // set to default data_sub_ = node->create_subscription( - source_topic, pointcloud_qos, - std::bind(&PointCloud::dataCallback, this, std::placeholders::_1)); + source_topic, + std::bind(&PointCloud::dataCallback, this, std::placeholders::_1), + nav2::qos::SensorDataQoS()); } bool PointCloud::getData( @@ -111,10 +111,10 @@ void PointCloud::getParameters(std::string & source_topic) getCommonParameters(source_topic); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name_ + ".min_height", rclcpp::ParameterValue(0.05)); min_height_ = node->get_parameter(source_name_ + ".min_height").as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name_ + ".max_height", rclcpp::ParameterValue(0.5)); max_height_ = node->get_parameter(source_name_ + ".max_height").as_double(); } diff --git a/nav2_collision_monitor/src/polygon.cpp b/nav2_collision_monitor/src/polygon.cpp index aeda547fd46..5e13f5d5ef8 100644 --- a/nav2_collision_monitor/src/polygon.cpp +++ b/nav2_collision_monitor/src/polygon.cpp @@ -21,7 +21,7 @@ #include "geometry_msgs/msg/point32.hpp" #include "tf2/transform_datatypes.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_util/array_parser.hpp" @@ -31,7 +31,7 @@ namespace nav2_collision_monitor { Polygon::Polygon( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -94,9 +94,8 @@ bool Polygon::configure() polygon_.polygon.points.push_back(p_s); } - rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS(); // set to default polygon_pub_ = node->create_publisher( - polygon_pub_topic, polygon_qos); + polygon_pub_topic); } // Add callback for dynamic parameters @@ -332,7 +331,7 @@ bool Polygon::getCommonParameters( try { // Get action type. // Leave it not initialized: the will cause an error if it will not set. - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".action_type", rclcpp::PARAMETER_STRING); const std::string at_str = node->get_parameter(polygon_name_ + ".action_type").as_string(); @@ -351,16 +350,16 @@ bool Polygon::getCommonParameters( return false; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".enabled", rclcpp::ParameterValue(true)); enabled_ = node->get_parameter(polygon_name_ + ".enabled").as_bool(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".min_points", rclcpp::ParameterValue(4)); min_points_ = node->get_parameter(polygon_name_ + ".min_points").as_int(); try { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".max_points", rclcpp::PARAMETER_INTEGER); min_points_ = node->get_parameter(polygon_name_ + ".max_points").as_int() + 1; RCLCPP_WARN( @@ -373,42 +372,42 @@ bool Polygon::getCommonParameters( } if (action_type_ == SLOWDOWN) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".slowdown_ratio", rclcpp::ParameterValue(0.5)); slowdown_ratio_ = node->get_parameter(polygon_name_ + ".slowdown_ratio").as_double(); } if (action_type_ == LIMIT) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".linear_limit", rclcpp::ParameterValue(0.5)); linear_limit_ = node->get_parameter(polygon_name_ + ".linear_limit").as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".angular_limit", rclcpp::ParameterValue(0.5)); angular_limit_ = node->get_parameter(polygon_name_ + ".angular_limit").as_double(); } if (action_type_ == APPROACH) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".time_before_collision", rclcpp::ParameterValue(2.0)); time_before_collision_ = node->get_parameter(polygon_name_ + ".time_before_collision").as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".simulation_time_step", rclcpp::ParameterValue(0.1)); simulation_time_step_ = node->get_parameter(polygon_name_ + ".simulation_time_step").as_double(); } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".visualize", rclcpp::ParameterValue(false)); visualize_ = node->get_parameter(polygon_name_ + ".visualize").as_bool(); if (visualize_) { // Get polygon topic parameter in case if it is going to be published - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".polygon_pub_topic", rclcpp::ParameterValue(polygon_name_)); polygon_pub_topic = node->get_parameter(polygon_name_ + ".polygon_pub_topic").as_string(); } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".polygon_subscribe_transient_local", rclcpp::ParameterValue(false)); polygon_subscribe_transient_local_ = node->get_parameter(polygon_name_ + ".polygon_subscribe_transient_local").as_bool(); @@ -416,13 +415,13 @@ bool Polygon::getCommonParameters( if (use_dynamic_sub_topic) { if (action_type_ != APPROACH) { // Get polygon sub topic - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".polygon_sub_topic", rclcpp::PARAMETER_STRING); polygon_sub_topic = node->get_parameter(polygon_name_ + ".polygon_sub_topic").as_string(); } else { // Obtain the footprint topic to make a footprint subscription for approach polygon - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".footprint_topic", rclcpp::ParameterValue("local_costmap/published_footprint")); footprint_topic = @@ -431,11 +430,11 @@ bool Polygon::getCommonParameters( } // By default, use all observation sources for polygon - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY); const std::vector observation_sources = node->get_parameter("observation_sources").as_string_array(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".sources_names", rclcpp::ParameterValue(observation_sources)); sources_names_ = node->get_parameter(polygon_name_ + ".sources_names").as_string_array(); @@ -480,7 +479,7 @@ bool Polygon::getParameters( bool use_dynamic_sub = true; // if getting parameter points fails, use dynamic subscription try { // Leave it uninitialized: it will throw an inner exception if the parameter is not set - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".points", rclcpp::PARAMETER_STRING); std::string poly_string = node->get_parameter(polygon_name_ + ".points").as_string(); @@ -521,13 +520,14 @@ void Polygon::createSubscription(std::string & polygon_sub_topic) logger_, "[%s]: Subscribing on %s topic for polygon", polygon_name_.c_str(), polygon_sub_topic.c_str()); - rclcpp::QoS polygon_qos = rclcpp::SystemDefaultsQoS(); // set to default + rclcpp::QoS polygon_qos = nav2::qos::StandardTopicQoS(); if (polygon_subscribe_transient_local_) { polygon_qos.transient_local(); } polygon_sub_ = node->create_subscription( - polygon_sub_topic, polygon_qos, - std::bind(&Polygon::polygonCallback, this, std::placeholders::_1)); + polygon_sub_topic, + std::bind(&Polygon::polygonCallback, this, std::placeholders::_1), + polygon_qos); } } diff --git a/nav2_collision_monitor/src/polygon_source.cpp b/nav2_collision_monitor/src/polygon_source.cpp index a147529670f..4d9b5589828 100644 --- a/nav2_collision_monitor/src/polygon_source.cpp +++ b/nav2_collision_monitor/src/polygon_source.cpp @@ -20,7 +20,7 @@ #include "geometry_msgs/msg/polygon_stamped.hpp" #include "tf2/transform_datatypes.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" @@ -28,7 +28,7 @@ namespace nav2_collision_monitor { PolygonSource::PolygonSource( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -59,10 +59,10 @@ void PolygonSource::configure() getParameters(source_topic); - rclcpp::QoS qos = rclcpp::SensorDataQoS(); // set to default data_sub_ = node->create_subscription( - source_topic, qos, - std::bind(&PolygonSource::dataCallback, this, std::placeholders::_1)); + source_topic, + std::bind(&PolygonSource::dataCallback, this, std::placeholders::_1), + nav2::qos::SensorDataQoS()); } bool PolygonSource::getData( @@ -160,7 +160,7 @@ void PolygonSource::getParameters(std::string & source_topic) getCommonParameters(source_topic); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name_ + ".sampling_distance", rclcpp::ParameterValue(0.1)); sampling_distance_ = node->get_parameter(source_name_ + ".sampling_distance").as_double(); } diff --git a/nav2_collision_monitor/src/range.cpp b/nav2_collision_monitor/src/range.cpp index d871c795082..2b91b40280f 100644 --- a/nav2_collision_monitor/src/range.cpp +++ b/nav2_collision_monitor/src/range.cpp @@ -20,14 +20,14 @@ #include "tf2/transform_datatypes.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" namespace nav2_collision_monitor { Range::Range( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -61,10 +61,10 @@ void Range::configure() getParameters(source_topic); - rclcpp::QoS range_qos = rclcpp::SensorDataQoS(); // set to default data_sub_ = node->create_subscription( - source_topic, range_qos, - std::bind(&Range::dataCallback, this, std::placeholders::_1)); + source_topic, + std::bind(&Range::dataCallback, this, std::placeholders::_1), + nav2::qos::SensorDataQoS()); } bool Range::getData( @@ -137,7 +137,7 @@ void Range::getParameters(std::string & source_topic) getCommonParameters(source_topic); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name_ + ".obstacles_angle", rclcpp::ParameterValue(M_PI / 180)); obstacles_angle_ = node->get_parameter(source_name_ + ".obstacles_angle").as_double(); } diff --git a/nav2_collision_monitor/src/scan.cpp b/nav2_collision_monitor/src/scan.cpp index 0bdcefcd66b..ce5fa7c89ec 100644 --- a/nav2_collision_monitor/src/scan.cpp +++ b/nav2_collision_monitor/src/scan.cpp @@ -25,7 +25,7 @@ namespace nav2_collision_monitor { Scan::Scan( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -60,10 +60,10 @@ void Scan::configure() // Laser scanner has no own parameters getCommonParameters(source_topic); - rclcpp::QoS scan_qos = rclcpp::SensorDataQoS(); // set to default data_sub_ = node->create_subscription( - source_topic, scan_qos, - std::bind(&Scan::dataCallback, this, std::placeholders::_1)); + source_topic, + std::bind(&Scan::dataCallback, this, std::placeholders::_1), + nav2::qos::SensorDataQoS()); } bool Scan::getData( diff --git a/nav2_collision_monitor/src/source.cpp b/nav2_collision_monitor/src/source.cpp index 50dc6e9ef96..9e4cfe37eda 100644 --- a/nav2_collision_monitor/src/source.cpp +++ b/nav2_collision_monitor/src/source.cpp @@ -18,14 +18,14 @@ #include "geometry_msgs/msg/transform_stamped.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" namespace nav2_collision_monitor { Source::Source( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -62,16 +62,16 @@ void Source::getCommonParameters(std::string & source_topic) throw std::runtime_error{"Failed to lock node"}; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name_ + ".topic", rclcpp::ParameterValue("scan")); // Set default topic for laser scanner source_topic = node->get_parameter(source_name_ + ".topic").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name_ + ".enabled", rclcpp::ParameterValue(true)); enabled_ = node->get_parameter(source_name_ + ".enabled").as_bool(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, source_name_ + ".source_timeout", rclcpp::ParameterValue(source_timeout_.seconds())); // node source_timeout by default source_timeout_ = rclcpp::Duration::from_seconds( diff --git a/nav2_collision_monitor/src/velocity_polygon.cpp b/nav2_collision_monitor/src/velocity_polygon.cpp index 602a018c2bb..1a391d22979 100644 --- a/nav2_collision_monitor/src/velocity_polygon.cpp +++ b/nav2_collision_monitor/src/velocity_polygon.cpp @@ -14,13 +14,13 @@ #include "nav2_collision_monitor/velocity_polygon.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_collision_monitor { VelocityPolygon::VelocityPolygon( - const nav2_util::LifecycleNode::WeakPtr & node, const std::string & polygon_name, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, const tf2::Duration & transform_tolerance) : Polygon::Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_tolerance) @@ -50,20 +50,20 @@ bool VelocityPolygon::getParameters( try { // Get velocity_polygons parameter - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".velocity_polygons", rclcpp::PARAMETER_STRING_ARRAY); std::vector velocity_polygons = node->get_parameter(polygon_name_ + ".velocity_polygons").as_string_array(); // holonomic param - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + ".holonomic", rclcpp::ParameterValue(false)); holonomic_ = node->get_parameter(polygon_name_ + ".holonomic").as_bool(); for (std::string velocity_polygon_name : velocity_polygons) { // polygon points parameter std::vector poly; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + "." + velocity_polygon_name + ".points", rclcpp::PARAMETER_STRING); std::string poly_string = node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".points").as_string(); @@ -74,7 +74,7 @@ bool VelocityPolygon::getParameters( // linear_min param double linear_min; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + "." + velocity_polygon_name + ".linear_min", rclcpp::PARAMETER_DOUBLE); linear_min = node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".linear_min") @@ -82,7 +82,7 @@ bool VelocityPolygon::getParameters( // linear_max param double linear_max; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + "." + velocity_polygon_name + ".linear_max", rclcpp::PARAMETER_DOUBLE); linear_max = node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".linear_max") @@ -90,7 +90,7 @@ bool VelocityPolygon::getParameters( // theta_min param double theta_min; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + "." + velocity_polygon_name + ".theta_min", rclcpp::PARAMETER_DOUBLE); theta_min = @@ -98,7 +98,7 @@ bool VelocityPolygon::getParameters( // theta_max param double theta_max; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + "." + velocity_polygon_name + ".theta_max", rclcpp::PARAMETER_DOUBLE); theta_max = @@ -108,14 +108,14 @@ bool VelocityPolygon::getParameters( double direction_end_angle = 0.0; double direction_start_angle = 0.0; if (holonomic_) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + "." + velocity_polygon_name + ".direction_end_angle", rclcpp::ParameterValue(M_PI)); direction_end_angle = node->get_parameter(polygon_name_ + "." + velocity_polygon_name + ".direction_end_angle") .as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, polygon_name_ + "." + velocity_polygon_name + ".direction_start_angle", rclcpp::ParameterValue(-M_PI)); direction_start_angle = diff --git a/nav2_collision_monitor/test/collision_detector_node_test.cpp b/nav2_collision_monitor/test/collision_detector_node_test.cpp index da2ecbc98e8..1bd2eb0ca0c 100644 --- a/nav2_collision_monitor/test/collision_detector_node_test.cpp +++ b/nav2_collision_monitor/test/collision_detector_node_test.cpp @@ -25,7 +25,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "sensor_msgs/msg/laser_scan.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "sensor_msgs/msg/range.hpp" @@ -79,25 +79,25 @@ class CollisionDetectorWrapper : public nav2_collision_monitor::CollisionDetecto public: void start() { - ASSERT_EQ(on_configure(get_current_state()), nav2_util::CallbackReturn::SUCCESS); - ASSERT_EQ(on_activate(get_current_state()), nav2_util::CallbackReturn::SUCCESS); + ASSERT_EQ(on_configure(get_current_state()), nav2::CallbackReturn::SUCCESS); + ASSERT_EQ(on_activate(get_current_state()), nav2::CallbackReturn::SUCCESS); } void stop() { - ASSERT_EQ(on_deactivate(get_current_state()), nav2_util::CallbackReturn::SUCCESS); - ASSERT_EQ(on_cleanup(get_current_state()), nav2_util::CallbackReturn::SUCCESS); - ASSERT_EQ(on_shutdown(get_current_state()), nav2_util::CallbackReturn::SUCCESS); + ASSERT_EQ(on_deactivate(get_current_state()), nav2::CallbackReturn::SUCCESS); + ASSERT_EQ(on_cleanup(get_current_state()), nav2::CallbackReturn::SUCCESS); + ASSERT_EQ(on_shutdown(get_current_state()), nav2::CallbackReturn::SUCCESS); } void configure() { - ASSERT_EQ(on_configure(get_current_state()), nav2_util::CallbackReturn::SUCCESS); + ASSERT_EQ(on_configure(get_current_state()), nav2::CallbackReturn::SUCCESS); } void cant_configure() { - ASSERT_EQ(on_configure(get_current_state()), nav2_util::CallbackReturn::FAILURE); + ASSERT_EQ(on_configure(get_current_state()), nav2::CallbackReturn::FAILURE); } bool correctDataReceived(const double expected_dist, const rclcpp::Time & stamp) @@ -157,16 +157,20 @@ class Tester : public ::testing::Test std::shared_ptr cd_; // Data source publishers - rclcpp::Publisher::SharedPtr scan_pub_; - rclcpp::Publisher::SharedPtr pointcloud_pub_; - rclcpp::Publisher::SharedPtr range_pub_; - rclcpp::Publisher::SharedPtr polygon_source_pub_; - - rclcpp::Subscription::SharedPtr state_sub_; + nav2::Publisher::SharedPtr + scan_pub_; + nav2::Publisher::SharedPtr + pointcloud_pub_; + nav2::Publisher::SharedPtr + range_pub_; + nav2::Publisher::SharedPtr + polygon_source_pub_; + + nav2::Subscription::SharedPtr state_sub_; nav2_msgs::msg::CollisionDetectorState::SharedPtr state_msg_; // CollisionMonitor collision points markers - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr collision_points_marker_sub_; visualization_msgs::msg::MarkerArray::SharedPtr collision_points_marker_msg_; }; // Tester @@ -177,27 +181,34 @@ Tester::Tester() scan_pub_ = cd_->create_publisher( SCAN_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + scan_pub_->on_activate(); pointcloud_pub_ = cd_->create_publisher( POINTCLOUD_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + pointcloud_pub_->on_activate(); range_pub_ = cd_->create_publisher( RANGE_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + range_pub_->on_activate(); polygon_source_pub_ = cd_->create_publisher( POLYGON_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + polygon_source_pub_->on_activate(); state_sub_ = cd_->create_subscription( - STATE_TOPIC, rclcpp::SystemDefaultsQoS(), + STATE_TOPIC, std::bind(&Tester::stateCallback, this, std::placeholders::_1)); collision_points_marker_sub_ = cd_->create_subscription( - COLLISION_POINTS_MARKERS_TOPIC, rclcpp::SystemDefaultsQoS(), + COLLISION_POINTS_MARKERS_TOPIC, std::bind(&Tester::collisionPointsMarkerCallback, this, std::placeholders::_1)); } Tester::~Tester() { scan_pub_.reset(); + pointcloud_pub_->on_deactivate(); pointcloud_pub_.reset(); + range_pub_->on_deactivate(); range_pub_.reset(); + polygon_source_pub_->on_deactivate(); polygon_source_pub_.reset(); collision_points_marker_sub_.reset(); diff --git a/nav2_collision_monitor/test/collision_monitor_node_test.cpp b/nav2_collision_monitor/test/collision_monitor_node_test.cpp index 2fda8571995..d64f0bd71e8 100644 --- a/nav2_collision_monitor/test/collision_monitor_node_test.cpp +++ b/nav2_collision_monitor/test/collision_monitor_node_test.cpp @@ -24,7 +24,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/msg/collision_monitor_state.hpp" #include "sensor_msgs/msg/laser_scan.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" @@ -96,25 +96,25 @@ class CollisionMonitorWrapper : public nav2_collision_monitor::CollisionMonitor public: void start() { - ASSERT_EQ(on_configure(get_current_state()), nav2_util::CallbackReturn::SUCCESS); - ASSERT_EQ(on_activate(get_current_state()), nav2_util::CallbackReturn::SUCCESS); + ASSERT_EQ(on_configure(get_current_state()), nav2::CallbackReturn::SUCCESS); + ASSERT_EQ(on_activate(get_current_state()), nav2::CallbackReturn::SUCCESS); } void stop() { - ASSERT_EQ(on_deactivate(get_current_state()), nav2_util::CallbackReturn::SUCCESS); - ASSERT_EQ(on_cleanup(get_current_state()), nav2_util::CallbackReturn::SUCCESS); - ASSERT_EQ(on_shutdown(get_current_state()), nav2_util::CallbackReturn::SUCCESS); + ASSERT_EQ(on_deactivate(get_current_state()), nav2::CallbackReturn::SUCCESS); + ASSERT_EQ(on_cleanup(get_current_state()), nav2::CallbackReturn::SUCCESS); + ASSERT_EQ(on_shutdown(get_current_state()), nav2::CallbackReturn::SUCCESS); } void configure() { - ASSERT_EQ(on_configure(get_current_state()), nav2_util::CallbackReturn::SUCCESS); + ASSERT_EQ(on_configure(get_current_state()), nav2::CallbackReturn::SUCCESS); } void cant_configure() { - ASSERT_EQ(on_configure(get_current_state()), nav2_util::CallbackReturn::FAILURE); + ASSERT_EQ(on_configure(get_current_state()), nav2::CallbackReturn::FAILURE); } bool correctDataReceived(const double expected_dist, const rclcpp::Time & stamp) @@ -190,31 +190,33 @@ class Tester : public ::testing::Test std::shared_ptr cm_; // Footprint publisher - rclcpp::Publisher::SharedPtr footprint_pub_; + nav2::Publisher::SharedPtr + footprint_pub_; // Data source publishers - rclcpp::Publisher::SharedPtr scan_pub_; - rclcpp::Publisher::SharedPtr pointcloud_pub_; - rclcpp::Publisher::SharedPtr range_pub_; - rclcpp::Publisher::SharedPtr polygon_source_pub_; + nav2::Publisher::SharedPtr scan_pub_; + nav2::Publisher::SharedPtr pointcloud_pub_; + nav2::Publisher::SharedPtr range_pub_; + nav2::Publisher::SharedPtr + polygon_source_pub_; // Working with cmd_vel_in/cmd_vel_out - rclcpp::Publisher::SharedPtr cmd_vel_in_pub_; - rclcpp::Subscription::SharedPtr cmd_vel_out_sub_; + nav2::Publisher::SharedPtr cmd_vel_in_pub_; + nav2::Subscription::SharedPtr cmd_vel_out_sub_; geometry_msgs::msg::Twist::SharedPtr cmd_vel_out_; // CollisionMonitor Action state - rclcpp::Subscription::SharedPtr action_state_sub_; + nav2::Subscription::SharedPtr action_state_sub_; nav2_msgs::msg::CollisionMonitorState::SharedPtr action_state_; // CollisionMonitor collision points markers - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr collision_points_marker_sub_; visualization_msgs::msg::MarkerArray::SharedPtr collision_points_marker_msg_; // Service client for setting CollisionMonitor parameters - rclcpp::Client::SharedPtr parameters_client_; + nav2::ServiceClient::SharedPtr parameters_client_; }; // Tester Tester::Tester() @@ -224,27 +226,33 @@ Tester::Tester() footprint_pub_ = cm_->create_publisher( FOOTPRINT_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + footprint_pub_->on_activate(); scan_pub_ = cm_->create_publisher( SCAN_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + scan_pub_->on_activate(); pointcloud_pub_ = cm_->create_publisher( POINTCLOUD_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + pointcloud_pub_->on_activate(); range_pub_ = cm_->create_publisher( RANGE_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + range_pub_->on_activate(); polygon_source_pub_ = cm_->create_publisher( POLYGON_NAME, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + polygon_source_pub_->on_activate(); cmd_vel_in_pub_ = cm_->create_publisher( CMD_VEL_IN_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + cmd_vel_in_pub_->on_activate(); cmd_vel_out_sub_ = cm_->create_subscription( - CMD_VEL_OUT_TOPIC, rclcpp::SystemDefaultsQoS(), + CMD_VEL_OUT_TOPIC, std::bind(&Tester::cmdVelOutCallback, this, std::placeholders::_1)); action_state_sub_ = cm_->create_subscription( - STATE_TOPIC, rclcpp::SystemDefaultsQoS(), + STATE_TOPIC, std::bind(&Tester::actionStateCallback, this, std::placeholders::_1)); collision_points_marker_sub_ = cm_->create_subscription( - COLLISION_POINTS_MARKERS_TOPIC, rclcpp::SystemDefaultsQoS(), + COLLISION_POINTS_MARKERS_TOPIC, std::bind(&Tester::collisionPointsMarkerCallback, this, std::placeholders::_1)); parameters_client_ = cm_->create_client( @@ -256,11 +264,16 @@ Tester::~Tester() { footprint_pub_.reset(); + scan_pub_->on_deactivate(); scan_pub_.reset(); + pointcloud_pub_->on_deactivate(); pointcloud_pub_.reset(); + range_pub_->on_deactivate(); range_pub_.reset(); + polygon_source_pub_->on_deactivate(); polygon_source_pub_.reset(); + cmd_vel_in_pub_->on_deactivate(); cmd_vel_in_pub_.reset(); cmd_vel_out_sub_.reset(); @@ -1353,7 +1366,7 @@ TEST_F(Tester, testPolygonNotEnabled) parameter_msg->value.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; parameter_msg->value.bool_value = false; set_parameters_msg->parameters.push_back(*parameter_msg); - auto result_future = parameters_client_->async_send_request(set_parameters_msg).future.share(); + auto result_future = parameters_client_->async_call(set_parameters_msg); ASSERT_TRUE(waitFuture(result_future, 2s)); // Check that robot does not stop when polygon is disabled @@ -1408,7 +1421,7 @@ TEST_F(Tester, testSourceNotEnabled) parameter_msg->value.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; parameter_msg->value.bool_value = false; set_parameters_msg->parameters.push_back(*parameter_msg); - auto result_future = parameters_client_->async_send_request(set_parameters_msg).future.share(); + auto result_future = parameters_client_->async_call(set_parameters_msg); ASSERT_TRUE(waitFuture(result_future, 2s)); // Check that robot does not stop when source is disabled diff --git a/nav2_collision_monitor/test/polygons_test.cpp b/nav2_collision_monitor/test/polygons_test.cpp index 6c27055437f..52eff3c650b 100644 --- a/nav2_collision_monitor/test/polygons_test.cpp +++ b/nav2_collision_monitor/test/polygons_test.cpp @@ -23,7 +23,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/point32.hpp" #include "geometry_msgs/msg/polygon_stamped.hpp" @@ -73,16 +73,12 @@ static const double TIME_BEFORE_COLLISION{1.0}; static const double SIMULATION_TIME_STEP{0.01}; static const tf2::Duration TRANSFORM_TOLERANCE{tf2::durationFromSec(0.1)}; -class TestNode : public nav2_util::LifecycleNode +class TestNode : public nav2::LifecycleNode { public: TestNode() - : nav2_util::LifecycleNode("test_node"), polygon_received_(nullptr) - { - polygon_sub_ = this->create_subscription( - POLYGON_PUB_TOPIC, rclcpp::SystemDefaultsQoS(), - std::bind(&TestNode::polygonCallback, this, std::placeholders::_1)); - } + : nav2::LifecycleNode("test_node"), polygon_received_(nullptr) + {} ~TestNode() { @@ -90,10 +86,19 @@ class TestNode : public nav2_util::LifecycleNode footprint_pub_.reset(); } + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & /*previous_state*/) override + { + polygon_sub_ = this->create_subscription( + POLYGON_PUB_TOPIC, + std::bind(&TestNode::polygonCallback, this, std::placeholders::_1)); + return nav2::CallbackReturn::SUCCESS; + } + void publishPolygon(const std::string & frame_id, const bool is_correct) { polygon_pub_ = this->create_publisher( POLYGON_SUB_TOPIC, rclcpp::SystemDefaultsQoS()); + polygon_pub_->on_activate(); std::unique_ptr msg = std::make_unique(); @@ -122,6 +127,7 @@ class TestNode : public nav2_util::LifecycleNode { radius_pub_ = this->create_publisher( POLYGON_SUB_TOPIC, rclcpp::SystemDefaultsQoS()); + radius_pub_->on_activate(); std::unique_ptr msg = std::make_unique(); msg->data = CIRCLE_RADIUS; @@ -133,6 +139,7 @@ class TestNode : public nav2_util::LifecycleNode { footprint_pub_ = this->create_publisher( FOOTPRINT_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + footprint_pub_->on_activate(); std::unique_ptr msg = std::make_unique(); @@ -170,10 +177,11 @@ class TestNode : public nav2_util::LifecycleNode } private: - rclcpp::Publisher::SharedPtr polygon_pub_; - rclcpp::Publisher::SharedPtr radius_pub_; - rclcpp::Publisher::SharedPtr footprint_pub_; - rclcpp::Subscription::SharedPtr polygon_sub_; + nav2::Publisher::SharedPtr polygon_pub_; + nav2::Publisher::SharedPtr radius_pub_; + nav2::Publisher::SharedPtr + footprint_pub_; + nav2::Subscription::SharedPtr polygon_sub_; geometry_msgs::msg::PolygonStamped::SharedPtr polygon_received_; }; // TestNode @@ -182,7 +190,7 @@ class PolygonWrapper : public nav2_collision_monitor::Polygon { public: PolygonWrapper( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -207,7 +215,7 @@ class CircleWrapper : public nav2_collision_monitor::Circle { public: CircleWrapper( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -277,6 +285,8 @@ class Tester : public ::testing::Test Tester::Tester() { test_node_ = std::make_shared(); + test_node_->configure(); + test_node_->activate(); tf_buffer_ = std::make_shared(test_node_->get_clock()); tf_buffer_->setUsingDedicatedThread(true); // One-thread broadcasting-listening model @@ -288,6 +298,8 @@ Tester::~Tester() polygon_.reset(); circle_.reset(); + test_node_->deactivate(); + test_node_->cleanup(); test_node_.reset(); tf_listener_.reset(); @@ -418,7 +430,7 @@ void Tester::createPolygon(const std::string & action_type, const bool is_static setPolygonParameters(SQUARE_POLYGON_STR, is_static); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(polygon_->configure()); polygon_->activate(); @@ -430,7 +442,7 @@ void Tester::createCircle(const std::string & action_type, const bool is_static) setCircleParameters(CIRCLE_RADIUS, is_static); circle_ = std::make_shared( - test_node_, CIRCLE_NAME, + test_node_->weak_from_this(), CIRCLE_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(circle_->configure()); circle_->activate(); @@ -589,7 +601,7 @@ TEST_F(Tester, testPolygonUndeclaredActionType) { // "action_type" parameter is not initialized polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(polygon_->configure()); // Check that "action_type" parameter is not set after configuring @@ -604,7 +616,7 @@ TEST_F(Tester, testPolygonUndeclaredPoints) test_node_->set_parameter( rclcpp::Parameter(std::string(POLYGON_NAME) + ".action_type", "stop")); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(polygon_->configure()); // Check that "points" and "polygon_sub_topic" parameters are not set after configuring @@ -618,7 +630,7 @@ TEST_F(Tester, testPolygonIncorrectActionType) setPolygonParameters(SQUARE_POLYGON_STR, true); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(polygon_->configure()); } @@ -634,7 +646,7 @@ TEST_F(Tester, testPolygonIncorrectPoints1) rclcpp::Parameter(std::string(POLYGON_NAME) + ".points", INCORRECT_POINTS_1_STR)); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(polygon_->configure()); } @@ -650,7 +662,7 @@ TEST_F(Tester, testPolygonIncorrectPoints2) rclcpp::Parameter(std::string(POLYGON_NAME) + ".points", INCORRECT_POINTS_2_STR)); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(polygon_->configure()); } @@ -668,7 +680,7 @@ TEST_F(Tester, testPolygonMaxPoints) rclcpp::Parameter(std::string(POLYGON_NAME) + ".max_points", max_points)); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(polygon_->configure()); EXPECT_EQ(polygon_->getMinPoints(), max_points + 1); @@ -679,7 +691,7 @@ TEST_F(Tester, testCircleUndeclaredRadius) setCommonParameters(CIRCLE_NAME, "stop"); circle_ = std::make_shared( - test_node_, CIRCLE_NAME, + test_node_->weak_from_this(), CIRCLE_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(circle_->configure()); @@ -837,7 +849,7 @@ TEST_F(Tester, testPolygonGetPointsInsideEdge) setPolygonParameters(ARBITRARY_POLYGON_STR, true); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(polygon_->configure()); @@ -975,7 +987,7 @@ TEST_F(Tester, testPolygonDefaultVisualize) // Create new polygon polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(polygon_->configure()); polygon_->activate(); @@ -998,7 +1010,7 @@ TEST_F(Tester, testPolygonInvalidPointsString) rclcpp::Parameter(std::string(POLYGON_NAME) + ".points", INVALID_POINTS_STR)); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(polygon_->configure()); } @@ -1010,7 +1022,7 @@ TEST_F(Tester, testPolygonSourceDefaultAssociation) setCommonParameters(POLYGON_NAME, "stop", all_sources); // no polygon sources names specified setPolygonParameters(SQUARE_POLYGON_STR, true); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(polygon_->configure()); ASSERT_EQ(polygon_->getSourcesNames(), all_sources); @@ -1023,7 +1035,7 @@ TEST_F(Tester, testPolygonSourceInvalidAssociation) POLYGON_NAME, "stop", {"source_1", "source_2", "source_3"}, {"source_1", "source_4"}); setPolygonParameters(SQUARE_POLYGON_STR, true); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_FALSE(polygon_->configure()); } @@ -1035,7 +1047,7 @@ TEST_F(Tester, testPolygonSourceAssociation) setCommonParameters(POLYGON_NAME, "stop", {"source_1", "source_2", "source_3"}, poly_sources); setPolygonParameters(SQUARE_POLYGON_STR, true); polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(polygon_->configure()); ASSERT_EQ(polygon_->getSourcesNames(), poly_sources); diff --git a/nav2_collision_monitor/test/sources_test.cpp b/nav2_collision_monitor/test/sources_test.cpp index 24de5cbe056..7ed6a7aa561 100644 --- a/nav2_collision_monitor/test/sources_test.cpp +++ b/nav2_collision_monitor/test/sources_test.cpp @@ -24,7 +24,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "sensor_msgs/msg/laser_scan.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "sensor_msgs/msg/range.hpp" @@ -58,11 +58,11 @@ static const char POLYGON_TOPIC[]{"polygon"}; static const tf2::Duration TRANSFORM_TOLERANCE{tf2::durationFromSec(0.1)}; static const rclcpp::Duration DATA_TIMEOUT{rclcpp::Duration::from_seconds(5.0)}; -class TestNode : public nav2_util::LifecycleNode +class TestNode : public nav2::LifecycleNode { public: TestNode() - : nav2_util::LifecycleNode("test_node") + : nav2::LifecycleNode("test_node") { } @@ -78,6 +78,7 @@ class TestNode : public nav2_util::LifecycleNode { scan_pub_ = this->create_publisher( SCAN_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + scan_pub_->on_activate(); std::unique_ptr msg = std::make_unique(); @@ -102,6 +103,7 @@ class TestNode : public nav2_util::LifecycleNode { pointcloud_pub_ = this->create_publisher( POINTCLOUD_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + pointcloud_pub_->on_activate(); std::unique_ptr msg = std::make_unique(); @@ -144,6 +146,7 @@ class TestNode : public nav2_util::LifecycleNode { range_pub_ = this->create_publisher( RANGE_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + range_pub_->on_activate(); std::unique_ptr msg = std::make_unique(); @@ -164,6 +167,7 @@ class TestNode : public nav2_util::LifecycleNode { polygon_pub_ = this->create_publisher( POLYGON_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + polygon_pub_->on_activate(); std::unique_ptr msg = std::make_unique(); @@ -193,17 +197,18 @@ class TestNode : public nav2_util::LifecycleNode } private: - rclcpp::Publisher::SharedPtr scan_pub_; - rclcpp::Publisher::SharedPtr pointcloud_pub_; - rclcpp::Publisher::SharedPtr range_pub_; - rclcpp::Publisher::SharedPtr polygon_pub_; + nav2::Publisher::SharedPtr scan_pub_; + nav2::Publisher::SharedPtr pointcloud_pub_; + nav2::Publisher::SharedPtr range_pub_; + nav2::Publisher::SharedPtr + polygon_pub_; }; // TestNode class ScanWrapper : public nav2_collision_monitor::Scan { public: ScanWrapper( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -226,7 +231,7 @@ class PointCloudWrapper : public nav2_collision_monitor::PointCloud { public: PointCloudWrapper( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -249,7 +254,7 @@ class RangeWrapper : public nav2_collision_monitor::Range { public: RangeWrapper( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -272,7 +277,7 @@ class PolygonWrapper : public nav2_collision_monitor::PolygonSource { public: PolygonWrapper( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & source_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, diff --git a/nav2_collision_monitor/test/velocity_polygons_test.cpp b/nav2_collision_monitor/test/velocity_polygons_test.cpp index bde3d9989ad..d13fc873340 100644 --- a/nav2_collision_monitor/test/velocity_polygons_test.cpp +++ b/nav2_collision_monitor/test/velocity_polygons_test.cpp @@ -23,7 +23,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/point32.hpp" #include "geometry_msgs/msg/polygon_stamped.hpp" @@ -68,19 +68,25 @@ static const bool IS_NOT_HOLONOMIC{false}; static const int MIN_POINTS{2}; static const tf2::Duration TRANSFORM_TOLERANCE{tf2::durationFromSec(0.1)}; -class TestNode : public nav2_util::LifecycleNode +class TestNode : public nav2::LifecycleNode { public: TestNode() - : nav2_util::LifecycleNode("test_node"), polygon_received_(nullptr) + : nav2::LifecycleNode("test_node"), polygon_received_(nullptr) { - polygon_sub_ = this->create_subscription( - POLYGON_PUB_TOPIC, rclcpp::SystemDefaultsQoS(), - std::bind(&TestNode::polygonCallback, this, std::placeholders::_1)); } ~TestNode() {} + nav2::CallbackReturn on_configure( + const rclcpp_lifecycle::State & /*previous_state*/) override + { + polygon_sub_ = this->create_subscription( + POLYGON_PUB_TOPIC, + std::bind(&TestNode::polygonCallback, this, std::placeholders::_1)); + return nav2::CallbackReturn::SUCCESS; + } + void polygonCallback(geometry_msgs::msg::PolygonStamped::SharedPtr msg) { polygon_received_ = msg; @@ -101,7 +107,7 @@ class TestNode : public nav2_util::LifecycleNode } private: - rclcpp::Subscription::SharedPtr polygon_sub_; + nav2::Subscription::SharedPtr polygon_sub_; geometry_msgs::msg::PolygonStamped::SharedPtr polygon_received_; }; // TestNode @@ -109,7 +115,7 @@ class VelocityPolygonWrapper : public nav2_collision_monitor::VelocityPolygon { public: VelocityPolygonWrapper( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & polygon_name, const std::shared_ptr tf_buffer, const std::string & base_frame_id, @@ -171,6 +177,8 @@ class Tester : public ::testing::Test Tester::Tester() { test_node_ = std::make_shared(); + test_node_->configure(); + test_node_->activate(); tf_buffer_ = std::make_shared(test_node_->get_clock()); tf_buffer_->setUsingDedicatedThread(true); // One-thread broadcasting-listening model @@ -358,7 +366,7 @@ void Tester::createVelocityPolygon(const std::string & action_type, const bool i setVelocityPolygonParameters(is_holonomic); velocity_polygon_ = std::make_shared( - test_node_, POLYGON_NAME, + test_node_->weak_from_this(), POLYGON_NAME, tf_buffer_, BASE_FRAME_ID, TRANSFORM_TOLERANCE); ASSERT_TRUE(velocity_polygon_->configure()); velocity_polygon_->activate(); diff --git a/nav2_constrained_smoother/CMakeLists.txt b/nav2_constrained_smoother/CMakeLists.txt index c859303edfa..92bcf17f79d 100644 --- a/nav2_constrained_smoother/CMakeLists.txt +++ b/nav2_constrained_smoother/CMakeLists.txt @@ -16,6 +16,7 @@ find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -29,6 +30,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC Ceres::ceres @@ -75,7 +77,7 @@ install(DIRECTORY include/ ament_export_include_directories(include/${PROJECT_NAME}) ament_export_libraries(${library_name}) -ament_export_dependencies(ceres eigen3 nav2_core nav2_costmap_2d nav2_util rclcpp rclcpp_lifecycle tf2_ros) +ament_export_dependencies(ceres eigen3 nav2_core nav2_ros_common nav2_costmap_2d nav2_util rclcpp rclcpp_lifecycle tf2_ros) ament_export_targets(${library_name}) pluginlib_export_plugin_description_file(nav2_core nav2_constrained_smoother.xml) diff --git a/nav2_constrained_smoother/include/nav2_constrained_smoother/constrained_smoother.hpp b/nav2_constrained_smoother/include/nav2_constrained_smoother/constrained_smoother.hpp index 4c276cdc696..0ae27093708 100644 --- a/nav2_constrained_smoother/include/nav2_constrained_smoother/constrained_smoother.hpp +++ b/nav2_constrained_smoother/include/nav2_constrained_smoother/constrained_smoother.hpp @@ -24,7 +24,7 @@ #include "nav2_core/smoother.hpp" #include "nav2_constrained_smoother/smoother.hpp" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/odometry_utils.hpp" #include "nav2_util/geometry_utils.hpp" @@ -56,7 +56,7 @@ class ConstrainedSmoother : public nav2_core::Smoother * @param costmap_ros Costmap2DROS object of environment */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_sub, std::shared_ptr footprint_sub) override; diff --git a/nav2_constrained_smoother/include/nav2_constrained_smoother/options.hpp b/nav2_constrained_smoother/include/nav2_constrained_smoother/options.hpp index 637443ebdd0..6c1f3fb33e4 100644 --- a/nav2_constrained_smoother/include/nav2_constrained_smoother/options.hpp +++ b/nav2_constrained_smoother/include/nav2_constrained_smoother/options.hpp @@ -19,8 +19,8 @@ #include #include #include -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "ceres/ceres.h" namespace nav2_constrained_smoother @@ -44,37 +44,37 @@ struct SmootherParams * @param node_ Ptr to node * @param name Name of plugin */ - void get(rclcpp_lifecycle::LifecycleNode * node, const std::string & name) + void get(nav2::LifecycleNode * node, const std::string & name) { std::string local_name = name + std::string("."); // Smoother params double minimum_turning_radius; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.4)); node->get_parameter(name + ".minimum_turning_radius", minimum_turning_radius); max_curvature = 1.0f / minimum_turning_radius; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_curve", rclcpp::ParameterValue(30.0)); node->get_parameter(local_name + "w_curve", curvature_weight); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_cost", rclcpp::ParameterValue(0.015)); node->get_parameter(local_name + "w_cost", costmap_weight); double cost_cusp_multiplier; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_cost_cusp_multiplier", rclcpp::ParameterValue(3.0)); node->get_parameter(local_name + "w_cost_cusp_multiplier", cost_cusp_multiplier); cusp_costmap_weight = costmap_weight * cost_cusp_multiplier; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "cusp_zone_length", rclcpp::ParameterValue(2.5)); node->get_parameter(local_name + "cusp_zone_length", cusp_zone_length); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_dist", rclcpp::ParameterValue(0.0)); node->get_parameter(local_name + "w_dist", distance_weight); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_smooth", rclcpp::ParameterValue(2000000.0)); node->get_parameter(local_name + "w_smooth", smooth_weight); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "cost_check_points", rclcpp::ParameterValue(std::vector())); node->get_parameter(local_name + "cost_check_points", cost_check_points); if (cost_check_points.size() % 3 != 0) { @@ -93,19 +93,19 @@ struct SmootherParams for (size_t i = 2u; i < cost_check_points.size(); i += 3) { cost_check_points[i] /= check_point_weights_sum; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "path_downsampling_factor", rclcpp::ParameterValue(1)); node->get_parameter(local_name + "path_downsampling_factor", path_downsampling_factor); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "path_upsampling_factor", rclcpp::ParameterValue(1)); node->get_parameter(local_name + "path_upsampling_factor", path_upsampling_factor); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "reversing_enabled", rclcpp::ParameterValue(true)); node->get_parameter(local_name + "reversing_enabled", reversing_enabled); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "keep_goal_orientation", rclcpp::ParameterValue(true)); node->get_parameter(local_name + "keep_goal_orientation", keep_goal_orientation); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "keep_start_orientation", rclcpp::ParameterValue(true)); node->get_parameter(local_name + "keep_start_orientation", keep_start_orientation); } @@ -146,12 +146,12 @@ struct OptimizerParams * @param node_ Ptr to node * @param name Name of plugin */ - void get(rclcpp_lifecycle::LifecycleNode * node, const std::string & name) + void get(nav2::LifecycleNode * node, const std::string & name) { std::string local_name = name + std::string(".optimizer."); // Optimizer params - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "linear_solver_type", rclcpp::ParameterValue("SPARSE_NORMAL_CHOLESKY")); node->get_parameter(local_name + "linear_solver_type", linear_solver_type); if (solver_types.find(linear_solver_type) == solver_types.end()) { @@ -167,19 +167,19 @@ struct OptimizerParams "Invalid linear_solver_type. Valid values are %s", valid_types_str.str().c_str()); throw std::runtime_error("Invalid parameter: linear_solver_type"); } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "param_tol", rclcpp::ParameterValue(1e-15)); node->get_parameter(local_name + "param_tol", param_tol); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "fn_tol", rclcpp::ParameterValue(1e-7)); node->get_parameter(local_name + "fn_tol", fn_tol); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "gradient_tol", rclcpp::ParameterValue(1e-10)); node->get_parameter(local_name + "gradient_tol", gradient_tol); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "max_iterations", rclcpp::ParameterValue(100)); node->get_parameter(local_name + "max_iterations", max_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "debug_optimizer", rclcpp::ParameterValue(false)); node->get_parameter(local_name + "debug_optimizer", debug); } diff --git a/nav2_constrained_smoother/package.xml b/nav2_constrained_smoother/package.xml index 09f4d27015c..11fb47b1b06 100644 --- a/nav2_constrained_smoother/package.xml +++ b/nav2_constrained_smoother/package.xml @@ -22,6 +22,7 @@ rclcpp rclcpp_lifecycle tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_constrained_smoother/src/constrained_smoother.cpp b/nav2_constrained_smoother/src/constrained_smoother.cpp index 6b5bef4a303..03ab36ec3ce 100644 --- a/nav2_constrained_smoother/src/constrained_smoother.cpp +++ b/nav2_constrained_smoother/src/constrained_smoother.cpp @@ -23,7 +23,7 @@ #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_constrained_smoother/constrained_smoother.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_core/smoother_exceptions.hpp" @@ -32,7 +32,7 @@ #include "tf2/utils.hpp" -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using nav2_util::geometry_utils::euclidean_distance; using namespace nav2_costmap_2d; // NOLINT @@ -40,7 +40,7 @@ namespace nav2_constrained_smoother { void ConstrainedSmoother::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_sub, std::shared_ptr) diff --git a/nav2_constrained_smoother/test/test_constrained_smoother.cpp b/nav2_constrained_smoother/test/test_constrained_smoother.cpp index c4bb7e52740..5ed42e23c97 100644 --- a/nav2_constrained_smoother/test/test_constrained_smoother.cpp +++ b/nav2_constrained_smoother/test/test_constrained_smoother.cpp @@ -38,7 +38,7 @@ class DummyCostmapSubscriber : public nav2_costmap_2d::CostmapSubscriber { public: DummyCostmapSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::string & topic_name) : CostmapSubscriber(node, topic_name) { @@ -108,8 +108,7 @@ class SmootherTest : public ::testing::Test void SetUp() override { node_lifecycle_ = - std::make_shared( - "ConstrainedSmootherTestNode", rclcpp::NodeOptions()); + std::make_shared("ConstrainedSmootherTestNode"); tf_buffer_ = std::make_shared(node_lifecycle_->get_clock()); auto timer_interface = std::make_shared( @@ -388,16 +387,16 @@ class SmootherTest : public ::testing::Test return output; } - std::shared_ptr node_lifecycle_; + nav2::LifecycleNode::SharedPtr node_lifecycle_; std::shared_ptr smoother_; std::shared_ptr tf_buffer_; std::shared_ptr costmap_sub_; std::shared_ptr footprint_sub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr path_poses_pub_orig_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr path_poses_pub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr path_poses_pub_; + nav2::Publisher::SharedPtr path_poses_pub_cmp_; std::shared_ptr costmap_pub_; diff --git a/nav2_controller/CMakeLists.txt b/nav2_controller/CMakeLists.txt index 3cfaeeb9bf2..ecc147cc2d2 100644 --- a/nav2_controller/CMakeLists.txt +++ b/nav2_controller/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -32,6 +33,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -60,6 +62,7 @@ target_include_directories(${executable_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${executable_name} PRIVATE rclcpp::rclcpp @@ -71,6 +74,7 @@ target_include_directories(simple_progress_checker PUBLIC "$" "$" + "$" ) target_link_libraries(simple_progress_checker PUBLIC ${geometry_msgs_TARGETS} @@ -90,6 +94,7 @@ target_include_directories(pose_progress_checker PUBLIC "$" "$" + "$" ) target_link_libraries(pose_progress_checker PUBLIC ${geometry_msgs_TARGETS} @@ -110,6 +115,7 @@ target_include_directories(simple_goal_checker PUBLIC "$" "$" + "$" ) target_link_libraries(simple_goal_checker PUBLIC ${geometry_msgs_TARGETS} @@ -131,6 +137,7 @@ target_include_directories(stopped_goal_checker PUBLIC "$" "$" + "$" ) target_link_libraries(stopped_goal_checker PUBLIC ${geometry_msgs_TARGETS} @@ -150,6 +157,7 @@ target_include_directories(position_goal_checker PUBLIC "$" "$" + "$" ) target_link_libraries(position_goal_checker PUBLIC ${geometry_msgs_TARGETS} @@ -214,6 +222,7 @@ ament_export_dependencies( pluginlib rclcpp rclcpp_lifecycle + nav2_ros_common rcl_interfaces tf2_ros ) diff --git a/nav2_controller/include/nav2_controller/controller_server.hpp b/nav2_controller/include/nav2_controller/controller_server.hpp index 082d74a5043..a112a3c9d66 100644 --- a/nav2_controller/include/nav2_controller/controller_server.hpp +++ b/nav2_controller/include/nav2_controller/controller_server.hpp @@ -30,8 +30,8 @@ #include "nav2_msgs/action/follow_path.hpp" #include "nav2_msgs/msg/speed_limit.hpp" #include "nav_2d_utils/odom_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/simple_action_server.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_util/twist_publisher.hpp" #include "pluginlib/class_loader.hpp" @@ -46,7 +46,7 @@ class ProgressChecker; * @brief This class hosts variety of plugins of different algorithms to * complete control tasks from the exposed FollowPath action server. */ -class ControllerServer : public nav2_util::LifecycleNode +class ControllerServer : public nav2::LifecycleNode { public: using ControllerMap = std::unordered_map; @@ -74,7 +74,7 @@ class ControllerServer : public nav2_util::LifecycleNode * @throw pluginlib::PluginlibException When failed to initialize controller * plugin */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activates member variables * @@ -83,7 +83,7 @@ class ControllerServer : public nav2_util::LifecycleNode * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivates member variables * @@ -92,7 +92,7 @@ class ControllerServer : public nav2_util::LifecycleNode * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Calls clean up states and resets member variables. * @@ -101,19 +101,19 @@ class ControllerServer : public nav2_util::LifecycleNode * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in Shutdown state * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; using Action = nav2_msgs::action::FollowPath; - using ActionServer = nav2_util::SimpleActionServer; + using ActionServer = nav2::SimpleActionServer; // Our action server implements the FollowPath action - std::unique_ptr action_server_; + typename ActionServer::SharedPtr action_server_; /** * @brief FollowPath action server callback. Handles action server updates and @@ -230,12 +230,12 @@ class ControllerServer : public nav2_util::LifecycleNode // The controller needs a costmap node std::shared_ptr costmap_ros_; - std::unique_ptr costmap_thread_; + std::unique_ptr costmap_thread_; // Publishers and subscribers std::unique_ptr odom_sub_; std::unique_ptr vel_publisher_; - rclcpp::Subscription::SharedPtr speed_limit_sub_; + nav2::Subscription::SharedPtr speed_limit_sub_; // Progress Checker Plugin pluginlib::ClassLoader progress_checker_loader_; diff --git a/nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp b/nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp index 48eb580c964..e91ce3306c9 100644 --- a/nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/pose_progress_checker.hpp @@ -19,7 +19,7 @@ #include #include "rclcpp/rclcpp.hpp" #include "nav2_controller/plugins/simple_progress_checker.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_controller { @@ -33,7 +33,7 @@ class PoseProgressChecker : public SimpleProgressChecker { public: void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) override; bool check(geometry_msgs::msg::PoseStamped & current_pose) override; diff --git a/nav2_controller/include/nav2_controller/plugins/position_goal_checker.hpp b/nav2_controller/include/nav2_controller/plugins/position_goal_checker.hpp index b3f151812f8..04eb7623ecb 100644 --- a/nav2_controller/include/nav2_controller/plugins/position_goal_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/position_goal_checker.hpp @@ -19,7 +19,7 @@ #include #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/goal_checker.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" @@ -37,7 +37,7 @@ class PositionGoalChecker : public nav2_core::GoalChecker ~PositionGoalChecker() override = default; void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name, const std::shared_ptr costmap_ros) override; diff --git a/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp b/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp index 8bb3d9a949f..76feabf256f 100644 --- a/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/simple_goal_checker.hpp @@ -40,7 +40,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/goal_checker.hpp" #include "rcl_interfaces/msg/set_parameters_result.hpp" @@ -60,7 +60,7 @@ class SimpleGoalChecker : public nav2_core::GoalChecker SimpleGoalChecker(); // Standard GoalChecker Interface void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name, const std::shared_ptr costmap_ros) override; void reset() override; diff --git a/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp b/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp index f7b9707711a..fcff9c1215b 100644 --- a/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/simple_progress_checker.hpp @@ -18,7 +18,7 @@ #include #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/progress_checker.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose2_d.hpp" @@ -35,7 +35,7 @@ class SimpleProgressChecker : public nav2_core::ProgressChecker { public: void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) override; bool check(geometry_msgs::msg::PoseStamped & current_pose) override; void reset() override; diff --git a/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp b/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp index e2f6ee0a465..e0094cf6f4d 100644 --- a/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp +++ b/nav2_controller/include/nav2_controller/plugins/stopped_goal_checker.hpp @@ -40,7 +40,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_controller/plugins/simple_goal_checker.hpp" namespace nav2_controller @@ -56,7 +56,7 @@ class StoppedGoalChecker : public SimpleGoalChecker StoppedGoalChecker(); // Standard GoalChecker Interface void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name, const std::shared_ptr costmap_ros) override; bool isGoalReached( diff --git a/nav2_controller/package.xml b/nav2_controller/package.xml index 1532aecbf07..16875164c0d 100644 --- a/nav2_controller/package.xml +++ b/nav2_controller/package.xml @@ -25,6 +25,7 @@ rclcpp_components rclcpp_lifecycle tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_controller/plugins/pose_progress_checker.cpp b/nav2_controller/plugins/pose_progress_checker.cpp index 1ac4d20e026..60dce419476 100644 --- a/nav2_controller/plugins/pose_progress_checker.cpp +++ b/nav2_controller/plugins/pose_progress_checker.cpp @@ -21,7 +21,7 @@ #include "nav_2d_utils/conversions.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose2_d.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "pluginlib/class_list_macros.hpp" using rcl_interfaces::msg::ParameterType; @@ -31,14 +31,14 @@ namespace nav2_controller { void PoseProgressChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { plugin_name_ = plugin_name; SimpleProgressChecker::initialize(parent, plugin_name); auto node = parent.lock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".required_movement_angle", rclcpp::ParameterValue(0.5)); node->get_parameter_or(plugin_name + ".required_movement_angle", required_movement_angle_, 0.5); diff --git a/nav2_controller/plugins/position_goal_checker.cpp b/nav2_controller/plugins/position_goal_checker.cpp index 3d7c6be44e5..9c43ca33125 100644 --- a/nav2_controller/plugins/position_goal_checker.cpp +++ b/nav2_controller/plugins/position_goal_checker.cpp @@ -17,7 +17,7 @@ #include #include "nav2_controller/plugins/position_goal_checker.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" using rcl_interfaces::msg::ParameterType; using std::placeholders::_1; @@ -34,17 +34,17 @@ PositionGoalChecker::PositionGoalChecker() } void PositionGoalChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name, const std::shared_ptr/*costmap_ros*/) { plugin_name_ = plugin_name; auto node = parent.lock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".xy_goal_tolerance", rclcpp::ParameterValue(0.25)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".stateful", rclcpp::ParameterValue(true)); diff --git a/nav2_controller/plugins/simple_goal_checker.cpp b/nav2_controller/plugins/simple_goal_checker.cpp index f4bd8173ac2..fbed608796d 100644 --- a/nav2_controller/plugins/simple_goal_checker.cpp +++ b/nav2_controller/plugins/simple_goal_checker.cpp @@ -39,7 +39,7 @@ #include "nav2_controller/plugins/simple_goal_checker.hpp" #include "pluginlib/class_list_macros.hpp" #include "angles/angles.h" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" @@ -62,20 +62,20 @@ SimpleGoalChecker::SimpleGoalChecker() } void SimpleGoalChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name, const std::shared_ptr/*costmap_ros*/) { plugin_name_ = plugin_name; auto node = parent.lock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".xy_goal_tolerance", rclcpp::ParameterValue(0.25)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".yaw_goal_tolerance", rclcpp::ParameterValue(0.25)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".stateful", rclcpp::ParameterValue(true)); diff --git a/nav2_controller/plugins/simple_progress_checker.cpp b/nav2_controller/plugins/simple_progress_checker.cpp index 001edbf5d62..6c00168b559 100644 --- a/nav2_controller/plugins/simple_progress_checker.cpp +++ b/nav2_controller/plugins/simple_progress_checker.cpp @@ -20,7 +20,7 @@ #include "nav_2d_utils/conversions.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose2_d.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "pluginlib/class_list_macros.hpp" using rcl_interfaces::msg::ParameterType; @@ -29,7 +29,7 @@ using std::placeholders::_1; namespace nav2_controller { void SimpleProgressChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { plugin_name_ = plugin_name; @@ -37,9 +37,9 @@ void SimpleProgressChecker::initialize( clock_ = node->get_clock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".required_movement_radius", rclcpp::ParameterValue(0.5)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".movement_time_allowance", rclcpp::ParameterValue(10.0)); // Scale is set to 0 by default, so if it was not set otherwise, set to 0 node->get_parameter_or(plugin_name + ".required_movement_radius", radius_, 0.5); diff --git a/nav2_controller/plugins/stopped_goal_checker.cpp b/nav2_controller/plugins/stopped_goal_checker.cpp index 7408d4db78a..b0fa689add6 100644 --- a/nav2_controller/plugins/stopped_goal_checker.cpp +++ b/nav2_controller/plugins/stopped_goal_checker.cpp @@ -39,7 +39,7 @@ #include #include "nav2_controller/plugins/stopped_goal_checker.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" using std::hypot; using std::fabs; @@ -56,7 +56,7 @@ StoppedGoalChecker::StoppedGoalChecker() } void StoppedGoalChecker::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name, const std::shared_ptr costmap_ros) { @@ -65,10 +65,10 @@ void StoppedGoalChecker::initialize( auto node = parent.lock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".rot_stopped_velocity", rclcpp::ParameterValue(0.25)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".trans_stopped_velocity", rclcpp::ParameterValue(0.25)); diff --git a/nav2_controller/plugins/test/goal_checker.cpp b/nav2_controller/plugins/test/goal_checker.cpp index 5faba1bdc79..4e819fe9946 100644 --- a/nav2_controller/plugins/test/goal_checker.cpp +++ b/nav2_controller/plugins/test/goal_checker.cpp @@ -39,7 +39,7 @@ #include "nav2_controller/plugins/simple_goal_checker.hpp" #include "nav2_controller/plugins/stopped_goal_checker.hpp" #include "nav_2d_utils/conversions.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "eigen3/Eigen/Geometry" using nav2_controller::SimpleGoalChecker; @@ -97,42 +97,42 @@ void trueFalse( checkMacro(gc0, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, true); checkMacro(gc1, x0, y0, theta0, x1, y1, theta1, xv, yv, thetav, false); } -class TestLifecycleNode : public nav2_util::LifecycleNode +class TestLifecycleNode : public nav2::LifecycleNode { public: explicit TestLifecycleNode(const std::string & name) - : nav2_util::LifecycleNode(name) + : nav2::LifecycleNode(name) { } - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onError(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onError(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } }; diff --git a/nav2_controller/plugins/test/progress_checker.cpp b/nav2_controller/plugins/test/progress_checker.cpp index 4c5e0b28a90..0791b9e9c27 100644 --- a/nav2_controller/plugins/test/progress_checker.cpp +++ b/nav2_controller/plugins/test/progress_checker.cpp @@ -39,48 +39,48 @@ #include "nav2_controller/plugins/simple_progress_checker.hpp" #include "nav2_controller/plugins/pose_progress_checker.hpp" #include "nav_2d_utils/conversions.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/geometry_utils.hpp" using nav2_controller::SimpleProgressChecker; using nav2_controller::PoseProgressChecker; -class TestLifecycleNode : public nav2_util::LifecycleNode +class TestLifecycleNode : public nav2::LifecycleNode { public: explicit TestLifecycleNode(const std::string & name) - : nav2_util::LifecycleNode(name) + : nav2::LifecycleNode(name) { } - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onError(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onError(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } }; diff --git a/nav2_controller/src/controller_server.cpp b/nav2_controller/src/controller_server.cpp index f404febe4da..26187087ec1 100644 --- a/nav2_controller/src/controller_server.cpp +++ b/nav2_controller/src/controller_server.cpp @@ -23,7 +23,7 @@ #include "nav2_core/controller_exceptions.hpp" #include "nav_2d_utils/conversions.hpp" #include "nav_2d_utils/tf_help.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_controller/controller_server.hpp" @@ -35,7 +35,7 @@ namespace nav2_controller { ControllerServer::ControllerServer(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("controller_server", "", options), +: nav2::LifecycleNode("controller_server", "", options), progress_checker_loader_("nav2_core", "nav2_core::ProgressChecker"), default_progress_checker_ids_{"progress_checker"}, default_progress_checker_types_{"nav2_controller::SimpleProgressChecker"}, @@ -79,7 +79,7 @@ ControllerServer::~ControllerServer() costmap_thread_.reset(); } -nav2_util::CallbackReturn +nav2::CallbackReturn ControllerServer::on_configure(const rclcpp_lifecycle::State & state) { auto node = shared_from_this(); @@ -90,7 +90,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_parameter("progress_checker_plugins", progress_checker_ids_); if (progress_checker_ids_ == default_progress_checker_ids_) { for (size_t i = 0; i < default_progress_checker_ids_.size(); ++i) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_progress_checker_ids_[i] + ".plugin", rclcpp::ParameterValue(default_progress_checker_types_[i])); } @@ -100,7 +100,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_parameter("goal_checker_plugins", goal_checker_ids_); if (goal_checker_ids_ == default_goal_checker_ids_) { for (size_t i = 0; i < default_goal_checker_ids_.size(); ++i) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_goal_checker_ids_[i] + ".plugin", rclcpp::ParameterValue(default_goal_checker_types_[i])); } @@ -109,7 +109,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_parameter("controller_plugins", controller_ids_); if (controller_ids_ == default_ids_) { for (size_t i = 0; i < default_ids_.size(); ++i) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_ids_[i] + ".plugin", rclcpp::ParameterValue(default_types_[i])); } @@ -133,11 +133,11 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) costmap_ros_->configure(); // Launch a thread to run the costmap node - costmap_thread_ = std::make_unique(costmap_ros_); + costmap_thread_ = std::make_unique(costmap_ros_); for (size_t i = 0; i != progress_checker_ids_.size(); i++) { try { - progress_checker_types_[i] = nav2_util::get_plugin_type_param( + progress_checker_types_[i] = nav2::get_plugin_type_param( node, progress_checker_ids_[i]); nav2_core::ProgressChecker::Ptr progress_checker = progress_checker_loader_.createUniqueInstance(progress_checker_types_[i]); @@ -151,7 +151,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_logger(), "Failed to create progress_checker. Exception: %s", ex.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } @@ -165,7 +165,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) for (size_t i = 0; i != goal_checker_ids_.size(); i++) { try { - goal_checker_types_[i] = nav2_util::get_plugin_type_param(node, goal_checker_ids_[i]); + goal_checker_types_[i] = nav2::get_plugin_type_param(node, goal_checker_ids_[i]); nav2_core::GoalChecker::Ptr goal_checker = goal_checker_loader_.createUniqueInstance(goal_checker_types_[i]); RCLCPP_INFO( @@ -178,7 +178,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_logger(), "Failed to create goal checker. Exception: %s", ex.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } @@ -192,7 +192,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) for (size_t i = 0; i != controller_ids_.size(); i++) { try { - controller_types_[i] = nav2_util::get_plugin_type_param(node, controller_ids_[i]); + controller_types_[i] = nav2::get_plugin_type_param(node, controller_ids_[i]); nav2_core::Controller::Ptr controller = lp_loader_.createUniqueInstance(controller_types_[i]); RCLCPP_INFO( @@ -207,7 +207,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) get_logger(), "Failed to create controller. Exception: %s", ex.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } @@ -220,7 +220,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) "Controller Server has %s controllers available.", controller_ids_concat_.c_str()); odom_sub_ = std::make_unique(node); - vel_publisher_ = std::make_unique(node, "cmd_vel", 1); + vel_publisher_ = std::make_unique(node, "cmd_vel"); double costmap_update_timeout_dbl; get_parameter("costmap_update_timeout", costmap_update_timeout_dbl); @@ -229,36 +229,34 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state) // Create the action server that we implement with our followPath method // This may throw due to real-time prioritization if user doesn't have real-time permissions try { - action_server_ = std::make_unique( - shared_from_this(), + action_server_ = create_action_server( "follow_path", std::bind(&ControllerServer::computeControl, this), nullptr, std::chrono::milliseconds(500), - true /*spin thread*/, rcl_action_server_get_default_options(), - use_realtime_priority_ /*soft realtime*/); + true /*spin thread*/, use_realtime_priority_ /*soft realtime*/); } catch (const std::runtime_error & e) { RCLCPP_ERROR(get_logger(), "Error creating action server! %s", e.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } // Set subscription to the speed limiting topic speed_limit_sub_ = create_subscription( - speed_limit_topic, rclcpp::QoS(10), + speed_limit_topic, std::bind(&ControllerServer::speedLimitCallback, this, std::placeholders::_1)); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); const auto costmap_ros_state = costmap_ros_->activate(); if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } ControllerMap::iterator it; for (it = controllers_.begin(); it != controllers_.end(); ++it) { @@ -275,10 +273,10 @@ ControllerServer::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -307,10 +305,10 @@ ControllerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -335,14 +333,14 @@ ControllerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) vel_publisher_.reset(); speed_limit_sub_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn ControllerServer::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool ControllerServer::findControllerId( diff --git a/nav2_controller/test/test_dynamic_parameters.cpp b/nav2_controller/test/test_dynamic_parameters.cpp index 40f4f55862a..2e29a97d03e 100644 --- a/nav2_controller/test/test_dynamic_parameters.cpp +++ b/nav2_controller/test/test_dynamic_parameters.cpp @@ -19,7 +19,7 @@ #include #include "gtest/gtest.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_controller/controller_server.hpp" #include "rclcpp/rclcpp.hpp" diff --git a/nav2_core/include/nav2_core/behavior.hpp b/nav2_core/include/nav2_core/behavior.hpp index ee18146473c..b2e00e8cf53 100644 --- a/nav2_core/include/nav2_core/behavior.hpp +++ b/nav2_core/include/nav2_core/behavior.hpp @@ -19,7 +19,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/buffer.h" #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp" @@ -55,7 +55,7 @@ class Behavior * @param costmap_ros A pointer to the costmap */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf, std::shared_ptr local_collision_checker, std::shared_ptr global_collision_checker) = 0; diff --git a/nav2_core/include/nav2_core/behavior_tree_navigator.hpp b/nav2_core/include/nav2_core/behavior_tree_navigator.hpp index 513aab335d3..87824c7fd31 100644 --- a/nav2_core/include/nav2_core/behavior_tree_navigator.hpp +++ b/nav2_core/include/nav2_core/behavior_tree_navigator.hpp @@ -23,7 +23,7 @@ #include "nav2_util/odometry_utils.hpp" #include "tf2_ros/buffer.h" #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "nav2_behavior_tree/bt_action_server.hpp" @@ -124,7 +124,7 @@ class NavigatorBase * @return bool If successful */ virtual bool on_configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, + nav2::LifecycleNode::WeakPtr parent_node, const std::vector & plugin_lib_names, const FeedbackUtils & feedback_utils, nav2_core::NavigatorMuxer * plugin_muxer, @@ -186,7 +186,7 @@ class BehaviorTreeNavigator : public NavigatorBase * @return bool If successful */ bool on_configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node, + nav2::LifecycleNode::WeakPtr parent_node, const std::vector & plugin_lib_names, const FeedbackUtils & feedback_utils, nav2_core::NavigatorMuxer * plugin_muxer, @@ -202,7 +202,8 @@ class BehaviorTreeNavigator : public NavigatorBase std::string default_bt_xml_filename = getDefaultBTFilepath(parent_node); // Create the Behavior Tree Action Server for this navigator - bt_action_server_ = std::make_unique>( + bt_action_server_ = + std::make_unique>( node, getName(), plugin_lib_names, @@ -273,7 +274,7 @@ class BehaviorTreeNavigator : public NavigatorBase return cleanup() && ok; } - virtual std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) = 0; + virtual std::string getDefaultBTFilepath(nav2::LifecycleNode::WeakPtr node) = 0; /** * @brief Get the action name of this navigator to expose @@ -345,7 +346,7 @@ class BehaviorTreeNavigator : public NavigatorBase * @param Method to configure resources. */ virtual bool configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr /*node*/, + nav2::LifecycleNode::WeakPtr /*node*/, std::shared_ptr/*odom_smoother*/) { return true; @@ -366,7 +367,8 @@ class BehaviorTreeNavigator : public NavigatorBase */ virtual bool deactivate() {return true;} - std::unique_ptr> bt_action_server_; + std::unique_ptr> + bt_action_server_; rclcpp::Logger logger_{rclcpp::get_logger("Navigator")}; rclcpp::Clock::SharedPtr clock_; FeedbackUtils feedback_utils_; diff --git a/nav2_core/include/nav2_core/controller.hpp b/nav2_core/include/nav2_core/controller.hpp index f9adaef0ac1..261eec22436 100644 --- a/nav2_core/include/nav2_core/controller.hpp +++ b/nav2_core/include/nav2_core/controller.hpp @@ -40,9 +40,8 @@ #include #include "nav2_costmap_2d/costmap_2d_ros.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/transform_listener.h" -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" @@ -73,7 +72,7 @@ class Controller * @param costmap_ros A pointer to the costmap */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string name, std::shared_ptr, std::shared_ptr) = 0; diff --git a/nav2_core/include/nav2_core/global_planner.hpp b/nav2_core/include/nav2_core/global_planner.hpp index 691acaa2340..bcf65da6d4f 100644 --- a/nav2_core/include/nav2_core/global_planner.hpp +++ b/nav2_core/include/nav2_core/global_planner.hpp @@ -17,12 +17,11 @@ #include #include -#include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "tf2_ros/buffer.h" #include "nav_msgs/msg/path.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_core { @@ -48,7 +47,7 @@ class GlobalPlanner * @param costmap_ros A pointer to the costmap */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) = 0; diff --git a/nav2_core/include/nav2_core/goal_checker.hpp b/nav2_core/include/nav2_core/goal_checker.hpp index 03e11c9a3e9..dfd2df96450 100644 --- a/nav2_core/include/nav2_core/goal_checker.hpp +++ b/nav2_core/include/nav2_core/goal_checker.hpp @@ -38,10 +38,9 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" #include "geometry_msgs/msg/pose.hpp" #include "geometry_msgs/msg/twist.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" @@ -70,7 +69,7 @@ class GoalChecker * @param parent Node pointer for grabbing parameters */ virtual void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name, const std::shared_ptr costmap_ros) = 0; diff --git a/nav2_core/include/nav2_core/progress_checker.hpp b/nav2_core/include/nav2_core/progress_checker.hpp index 0ab0402bf13..c95d601e11d 100644 --- a/nav2_core/include/nav2_core/progress_checker.hpp +++ b/nav2_core/include/nav2_core/progress_checker.hpp @@ -19,7 +19,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose2_d.hpp" @@ -43,7 +43,7 @@ class ProgressChecker * @param parent Node pointer */ virtual void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) = 0; /** * @brief Checks if the robot has moved compare to previous diff --git a/nav2_core/include/nav2_core/smoother.hpp b/nav2_core/include/nav2_core/smoother.hpp index e58b4a5ec62..7705106177d 100644 --- a/nav2_core/include/nav2_core/smoother.hpp +++ b/nav2_core/include/nav2_core/smoother.hpp @@ -22,8 +22,7 @@ #include "nav2_costmap_2d/footprint_subscriber.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "nav_msgs/msg/path.hpp" @@ -46,7 +45,7 @@ class Smoother virtual ~Smoother() {} virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string name, std::shared_ptr, std::shared_ptr, std::shared_ptr) = 0; diff --git a/nav2_core/include/nav2_core/waypoint_task_executor.hpp b/nav2_core/include/nav2_core/waypoint_task_executor.hpp index ffdbfd95e1d..3f735583b03 100644 --- a/nav2_core/include/nav2_core/waypoint_task_executor.hpp +++ b/nav2_core/include/nav2_core/waypoint_task_executor.hpp @@ -19,8 +19,7 @@ #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" namespace nav2_core @@ -51,7 +50,7 @@ class WaypointTaskExecutor * @param plugin_name plugin name comes from parameters in yaml file */ virtual void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) = 0; /** diff --git a/nav2_costmap_2d/CMakeLists.txt b/nav2_costmap_2d/CMakeLists.txt index fc8b8071d8d..ee9b7dabaa1 100644 --- a/nav2_costmap_2d/CMakeLists.txt +++ b/nav2_costmap_2d/CMakeLists.txt @@ -22,6 +22,7 @@ find_package(std_srvs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) find_package(tf2_sensor_msgs REQUIRED) find_package(visualization_msgs REQUIRED) @@ -45,6 +46,7 @@ target_include_directories(nav2_costmap_2d_core PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_costmap_2d_core PUBLIC ${geometry_msgs_TARGETS} @@ -73,6 +75,7 @@ target_include_directories(layers PUBLIC "$" "$" + "$" ) target_link_libraries(layers PUBLIC angles::angles @@ -96,6 +99,7 @@ target_include_directories(filters PUBLIC "$" "$" + "$" ) target_link_libraries(filters PUBLIC nav2_costmap_2d_core @@ -112,6 +116,7 @@ target_include_directories(nav2_costmap_2d_client PUBLIC "$" "$" + "$" ) target_link_libraries(nav2_costmap_2d_client PUBLIC nav2_costmap_2d_core @@ -126,6 +131,13 @@ target_link_libraries(nav2_costmap_2d_markers PRIVATE nav2_util::nav2_util_core rclcpp::rclcpp ${visualization_msgs_TARGETS} + nav2_ros_common::nav2_ros_common +) +target_include_directories(nav2_costmap_2d_markers + PUBLIC + "$" + "$" + "$" ) add_executable(nav2_costmap_2d_cloud src/costmap_2d_cloud.cpp) @@ -136,6 +148,13 @@ target_link_libraries(nav2_costmap_2d_cloud PRIVATE rclcpp::rclcpp ${sensor_msgs_TARGETS} ${std_msgs_TARGETS} + nav2_ros_common::nav2_ros_common +) +target_include_directories(nav2_costmap_2d_cloud + PUBLIC + "$" + "$" + "$" ) add_executable(nav2_costmap_2d src/costmap_2d_node.cpp) @@ -201,6 +220,7 @@ ament_export_dependencies( tf2 tf2_ros tf2_sensor_msgs + nav2_ros_common ) pluginlib_export_plugin_description_file(nav2_costmap_2d costmap_plugins.xml) ament_package() diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp index eae9a90b524..231c946014d 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp @@ -24,8 +24,8 @@ #include "nav2_msgs/srv/clear_costmap_around_robot.hpp" #include "nav2_msgs/srv/clear_entire_costmap.hpp" #include "nav2_costmap_2d/costmap_layer.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_server.hpp" namespace nav2_costmap_2d { @@ -43,7 +43,7 @@ class ClearCostmapService * @brief A constructor */ ClearCostmapService( - const nav2_util::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap); + const nav2::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap); /** * @brief A constructor @@ -76,8 +76,8 @@ class ClearCostmapService unsigned char reset_value_; // Server for clearing the costmap - nav2_util::ServiceServer>::SharedPtr clear_except_service_; + nav2::ServiceServer::SharedPtr + clear_except_service_; /** * @brief Callback to clear costmap except in a given region */ @@ -86,8 +86,8 @@ class ClearCostmapService const std::shared_ptr request, const std::shared_ptr response); - nav2_util::ServiceServer>::SharedPtr clear_around_service_; + nav2::ServiceServer::SharedPtr + clear_around_service_; /** * @brief Callback to clear costmap in a given region */ @@ -96,8 +96,8 @@ class ClearCostmapService const std::shared_ptr request, const std::shared_ptr response); - nav2_util::ServiceServer>::SharedPtr clear_entire_service_; + nav2::ServiceServer::SharedPtr + clear_entire_service_; /** * @brief Callback to clear costmap */ diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp index d6e1b8038b3..a6247e7d120 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_publisher.hpp @@ -51,10 +51,10 @@ #include "nav2_msgs/msg/costmap_update.hpp" #include "nav2_msgs/srv/get_costmap.hpp" #include "tf2/transform_datatypes.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2/LinearMath/Quaternion.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/service_server.hpp" namespace nav2_costmap_2d { @@ -69,7 +69,7 @@ class Costmap2DPublisher * @brief Constructor for the Costmap2DPublisher */ Costmap2DPublisher( - const nav2_util::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, Costmap2D * costmap, std::string global_frame, std::string topic_name, @@ -171,18 +171,17 @@ class Costmap2DPublisher double map_vis_z_; // Publisher for translated costmap values as msg::OccupancyGrid used in visualization - rclcpp_lifecycle::LifecyclePublisher::SharedPtr costmap_pub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr costmap_pub_; + nav2::Publisher::SharedPtr costmap_update_pub_; // Publisher for raw costmap values as msg::Costmap from layered costmap - rclcpp_lifecycle::LifecyclePublisher::SharedPtr costmap_raw_pub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr costmap_raw_pub_; + nav2::Publisher::SharedPtr costmap_raw_update_pub_; // Service for getting the costmaps - nav2_util::ServiceServer>::SharedPtr + nav2::ServiceServer::SharedPtr costmap_service_; float grid_resolution_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp index 8bd71add71d..878b7e6ecc5 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp @@ -51,7 +51,7 @@ #include "nav2_costmap_2d/clear_costmap_service.hpp" #include "nav2_costmap_2d/layered_costmap.hpp" #include "nav2_costmap_2d/layer.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/srv/get_costs.hpp" #include "pluginlib/class_loader.hpp" #include "tf2/convert.hpp" @@ -60,7 +60,7 @@ #include "tf2_ros/transform_listener.h" #include "tf2/time.hpp" #include "tf2/transform_datatypes.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/service_server.hpp" #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpedantic" @@ -73,7 +73,7 @@ namespace nav2_costmap_2d /** @brief A ROS wrapper for a 2D Costmap. Handles subscribing to * topics that provide observations about obstacles in either the form * of PointCloud or LaserScan messages. */ -class Costmap2DROS : public nav2_util::LifecycleNode +class Costmap2DROS : public nav2::LifecycleNode { public: /** @@ -107,27 +107,27 @@ class Costmap2DROS : public nav2_util::LifecycleNode /** * @brief Configure node */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activate node */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivate node */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Cleanup node */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief shutdown node */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** * @brief as a child-LifecycleNode : @@ -344,19 +344,19 @@ class Costmap2DROS : public nav2_util::LifecycleNode protected: // Publishers and subscribers - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr footprint_pub_; std::unique_ptr costmap_publisher_; std::vector> layer_publishers_; - rclcpp::Subscription::SharedPtr footprint_sub_; - rclcpp::Subscription::SharedPtr parameter_sub_; + nav2::Subscription::SharedPtr footprint_sub_; + nav2::Subscription::SharedPtr parameter_sub_; // Dedicated callback group and executor for tf timer_interface and message filter rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; - std::unique_ptr executor_thread_; + std::unique_ptr executor_thread_; // Transform listener std::shared_ptr tf_buffer_; @@ -416,8 +416,7 @@ class Costmap2DROS : public nav2_util::LifecycleNode std::vector padded_footprint_; // Services - nav2_util::ServiceServer>::SharedPtr get_cost_service_; + nav2::ServiceServer::SharedPtr get_cost_service_; std::unique_ptr clear_costmap_service_; // Dynamic parameters handler diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/binary_filter.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/binary_filter.hpp index 86a7e73669c..3cce5a112fc 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/binary_filter.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/binary_filter.hpp @@ -102,10 +102,10 @@ class BinaryFilter : public CostmapFilter void changeState(const bool state); // Working with filter info and mask - rclcpp::Subscription::SharedPtr filter_info_sub_; - rclcpp::Subscription::SharedPtr mask_sub_; + nav2::Subscription::SharedPtr filter_info_sub_; + nav2::Subscription::SharedPtr mask_sub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr binary_state_pub_; + nav2::Publisher::SharedPtr binary_state_pub_; nav_msgs::msg::OccupancyGrid::SharedPtr filter_mask_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp index 00a3cb833c1..f55f3092276 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/costmap_filter.hpp @@ -49,7 +49,7 @@ #include "std_srvs/srv/set_bool.hpp" #include "nav2_costmap_2d/layer.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/service_server.hpp" namespace nav2_costmap_2d { @@ -242,8 +242,7 @@ class CostmapFilter : public Layer /** * @brief: A service to enable/disable costmap filter */ - nav2_util::ServiceServer>::SharedPtr enable_service_; + nav2::ServiceServer::SharedPtr enable_service_; private: /** diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/keepout_filter.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/keepout_filter.hpp index a705c74f99a..c29c4c73bde 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/keepout_filter.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/keepout_filter.hpp @@ -96,8 +96,8 @@ class KeepoutFilter : public CostmapFilter */ void maskCallback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg); - rclcpp::Subscription::SharedPtr filter_info_sub_; - rclcpp::Subscription::SharedPtr mask_sub_; + nav2::Subscription::SharedPtr filter_info_sub_; + nav2::Subscription::SharedPtr mask_sub_; nav_msgs::msg::OccupancyGrid::SharedPtr filter_mask_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/speed_filter.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/speed_filter.hpp index cbce0e8767d..9f36728c0e5 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/speed_filter.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_filters/speed_filter.hpp @@ -96,10 +96,10 @@ class SpeedFilter : public CostmapFilter */ void maskCallback(const nav_msgs::msg::OccupancyGrid::SharedPtr msg); - rclcpp::Subscription::SharedPtr filter_info_sub_; - rclcpp::Subscription::SharedPtr mask_sub_; + nav2::Subscription::SharedPtr filter_info_sub_; + nav2::Subscription::SharedPtr mask_sub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr speed_limit_pub_; + nav2::Publisher::SharedPtr speed_limit_pub_; nav_msgs::msg::OccupancyGrid::SharedPtr filter_mask_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp index 955a8c80af4..c817125f50d 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp @@ -22,7 +22,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_msgs/msg/costmap.hpp" #include "nav2_msgs/msg/costmap_update.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_costmap_2d { @@ -37,15 +37,29 @@ class CostmapSubscriber * @brief A constructor */ CostmapSubscriber( - const nav2_util::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & topic_name); - /** - * @brief A constructor - */ + template CostmapSubscriber( - const rclcpp::Node::WeakPtr & parent, - const std::string & topic_name); + const NodeT & parent, + const std::string & topic_name) + : topic_name_(topic_name) + { + logger_ = parent->get_logger(); + + // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the + // subscription to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode + costmap_sub_ = nav2::interfaces::create_subscription( + parent, topic_name_, + std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); + + costmap_update_sub_ = nav2::interfaces::create_subscription( + parent, topic_name_ + "_updates", + std::bind(&CostmapSubscriber::costmapUpdateCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); + } /** * @brief A destructor @@ -79,8 +93,8 @@ class CostmapSubscriber bool hasCostmapResolutionChanged(); bool hasCostmapOriginPositionChanged(); - rclcpp::Subscription::SharedPtr costmap_sub_; - rclcpp::Subscription::SharedPtr costmap_update_sub_; + nav2::Subscription::SharedPtr costmap_sub_; + nav2::Subscription::SharedPtr costmap_update_sub_; std::shared_ptr costmap_; nav2_msgs::msg::Costmap::SharedPtr costmap_msg_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp index 6590a4682ec..bde3bc08f3c 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp @@ -47,7 +47,7 @@ #include "geometry_msgs/msg/polygon_stamped.hpp" #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/point32.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_costmap_2d { diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp index d9e9ddb3c6e..8996b81acf0 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/footprint_subscriber.hpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/footprint.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/robot_utils.hpp" namespace nav2_costmap_2d @@ -36,22 +36,23 @@ class FootprintSubscriber /** * @brief A constructor */ - FootprintSubscriber( - const nav2_util::LifecycleNode::WeakPtr & parent, + template + explicit FootprintSubscriber( + const NodeT & parent, const std::string & topic_name, tf2_ros::Buffer & tf, std::string robot_base_frame = "base_link", - double transform_tolerance = 0.1); - - /** - * @brief A constructor - */ - FootprintSubscriber( - const rclcpp::Node::WeakPtr & parent, - const std::string & topic_name, - tf2_ros::Buffer & tf, - std::string robot_base_frame = "base_link", - double transform_tolerance = 0.1); + double transform_tolerance = 0.1) + : tf_(tf), + robot_base_frame_(robot_base_frame), + transform_tolerance_(transform_tolerance) + { + // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the + // subscription to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode + footprint_sub_ = nav2::interfaces::create_subscription( + parent, topic_name, + std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1)); + } /** * @brief A destructor @@ -91,7 +92,7 @@ class FootprintSubscriber double transform_tolerance_; bool footprint_received_{false}; geometry_msgs::msg::PolygonStamped::SharedPtr footprint_; - rclcpp::Subscription::SharedPtr footprint_sub_; + nav2::Subscription::SharedPtr footprint_sub_; }; } // namespace nav2_costmap_2d diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp index 7c78424f02b..2136db7c856 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/layer.hpp @@ -45,7 +45,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/layered_costmap.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_costmap_2d { @@ -74,7 +74,7 @@ class Layer LayeredCostmap * parent, std::string name, tf2_ros::Buffer * tf, - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, rclcpp::CallbackGroup::SharedPtr callback_group); /** @brief Stop publishers. */ virtual void deactivate() {} @@ -184,7 +184,7 @@ class Layer std::string name_; tf2_ros::Buffer * tf_; rclcpp::CallbackGroup::SharedPtr callback_group_; - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; rclcpp::Clock::SharedPtr clock_; rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")}; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp index 2ff834a41e7..c54d586b729 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/observation_buffer.hpp @@ -47,7 +47,7 @@ #include "tf2_sensor_msgs/tf2_sensor_msgs.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "nav2_costmap_2d/observation.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_costmap_2d @@ -76,7 +76,7 @@ class ObservationBuffer * @param tf_tolerance The amount of time to wait for a transform to be available when setting a new global frame */ ObservationBuffer( - const nav2_util::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string topic_name, double observation_keep_time, double expected_update_rate, diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/range_sensor_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/range_sensor_layer.hpp index 3f5fce1537f..bb17f033d76 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/range_sensor_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/range_sensor_layer.hpp @@ -213,7 +213,7 @@ class RangeSensorLayer : public CostmapLayer double no_readings_timeout_; rclcpp::Time last_reading_time_; unsigned int buffered_readings_; - std::vector::SharedPtr> range_subs_; + std::vector::SharedPtr> range_subs_; double min_x_, min_y_, max_x_, max_y_; /** diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp index 307385bd4a8..7da443ebd25 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp @@ -182,8 +182,8 @@ class StaticLayer : public CostmapLayer unsigned int width_{0}; unsigned int height_{0}; - rclcpp::Subscription::SharedPtr map_sub_; - rclcpp::Subscription::SharedPtr map_update_sub_; + nav2::Subscription::SharedPtr map_sub_; + nav2::Subscription::SharedPtr map_update_sub_; // Parameters std::string map_topic_; diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp index 477020a3b65..c71072e1f6a 100644 --- a/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp +++ b/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp @@ -142,11 +142,11 @@ class VoxelLayer : public ObstacleLayer double * max_y); bool publish_voxel_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr voxel_pub_; + nav2::Publisher::SharedPtr voxel_pub_; nav2_voxel_grid::VoxelGrid voxel_grid_; double z_resolution_, origin_z_; int unknown_threshold_, mark_threshold_, size_z_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr clearing_endpoints_pub_; /** diff --git a/nav2_costmap_2d/package.xml b/nav2_costmap_2d/package.xml index 9a7e1146cb8..c01e7bb2dd6 100644 --- a/nav2_costmap_2d/package.xml +++ b/nav2_costmap_2d/package.xml @@ -40,6 +40,7 @@ tf2_ros tf2_sensor_msgs visualization_msgs + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_costmap_2d/plugins/costmap_filters/binary_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/binary_filter.cpp index 78b761e8d33..68a7c7adea4 100644 --- a/nav2_costmap_2d/plugins/costmap_filters/binary_filter.cpp +++ b/nav2_costmap_2d/plugins/costmap_filters/binary_filter.cpp @@ -60,7 +60,7 @@ void BinaryFilter::initializeFilter( { std::lock_guard guard(*getMutex()); - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } @@ -81,15 +81,16 @@ void BinaryFilter::initializeFilter( "BinaryFilter: Subscribing to \"%s\" topic for filter info...", filter_info_topic_.c_str()); filter_info_sub_ = node->create_subscription( - filter_info_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&BinaryFilter::filterInfoCallback, this, std::placeholders::_1)); + filter_info_topic_, + std::bind(&BinaryFilter::filterInfoCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); // Get global frame required for binary state publisher global_frame_ = layered_costmap_->getGlobalFrameID(); // Create new binary state publisher binary_state_pub_ = node->create_publisher( - binary_state_topic, rclcpp::QoS(10)); + binary_state_topic); binary_state_pub_->on_activate(); // Reset parameters @@ -105,7 +106,7 @@ void BinaryFilter::filterInfoCallback( { std::lock_guard guard(*getMutex()); - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } @@ -140,8 +141,9 @@ void BinaryFilter::filterInfoCallback( "BinaryFilter: Subscribing to \"%s\" topic for filter mask...", mask_topic_.c_str()); mask_sub_ = node->create_subscription( - mask_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&BinaryFilter::maskCallback, this, std::placeholders::_1)); + mask_topic_, + std::bind(&BinaryFilter::maskCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); } void BinaryFilter::maskCallback( diff --git a/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp index 6a5d83dd583..1a089b69122 100644 --- a/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp +++ b/nav2_costmap_2d/plugins/costmap_filters/costmap_filter.cpp @@ -64,7 +64,7 @@ CostmapFilter::~CostmapFilter() void CostmapFilter::onInitialize() { - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } @@ -83,10 +83,8 @@ void CostmapFilter::onInitialize() transform_tolerance_ = tf2::durationFromSec(transform_tolerance); // Costmap Filter enabling service - enable_service_ = std::make_shared>>( + enable_service_ = node->create_service( name_ + "/toggle_filter", - node, std::bind(&CostmapFilter::enableCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); } catch (const std::exception & ex) { diff --git a/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp index 0f24178e36d..af4c2fbb54c 100644 --- a/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp +++ b/nav2_costmap_2d/plugins/costmap_filters/keepout_filter.cpp @@ -58,7 +58,7 @@ void KeepoutFilter::initializeFilter( { std::lock_guard guard(*getMutex()); - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } @@ -70,8 +70,9 @@ void KeepoutFilter::initializeFilter( "KeepoutFilter: Subscribing to \"%s\" topic for filter info...", filter_info_topic_.c_str()); filter_info_sub_ = node->create_subscription( - filter_info_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&KeepoutFilter::filterInfoCallback, this, std::placeholders::_1)); + filter_info_topic_, + std::bind(&KeepoutFilter::filterInfoCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); global_frame_ = layered_costmap_->getGlobalFrameID(); @@ -90,7 +91,7 @@ void KeepoutFilter::filterInfoCallback( { std::lock_guard guard(*getMutex()); - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } @@ -125,8 +126,9 @@ void KeepoutFilter::filterInfoCallback( "KeepoutFilter: Subscribing to \"%s\" topic for filter mask...", mask_topic_.c_str()); mask_sub_ = node->create_subscription( - mask_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&KeepoutFilter::maskCallback, this, std::placeholders::_1)); + mask_topic_, + std::bind(&KeepoutFilter::maskCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); } void KeepoutFilter::maskCallback( @@ -134,7 +136,7 @@ void KeepoutFilter::maskCallback( { std::lock_guard guard(*getMutex()); - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } diff --git a/nav2_costmap_2d/plugins/costmap_filters/speed_filter.cpp b/nav2_costmap_2d/plugins/costmap_filters/speed_filter.cpp index 225cd4062d0..7a0d062ee19 100644 --- a/nav2_costmap_2d/plugins/costmap_filters/speed_filter.cpp +++ b/nav2_costmap_2d/plugins/costmap_filters/speed_filter.cpp @@ -59,7 +59,7 @@ void SpeedFilter::initializeFilter( { std::lock_guard guard(*getMutex()); - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } @@ -77,15 +77,16 @@ void SpeedFilter::initializeFilter( "SpeedFilter: Subscribing to \"%s\" topic for filter info...", filter_info_topic_.c_str()); filter_info_sub_ = node->create_subscription( - filter_info_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&SpeedFilter::filterInfoCallback, this, std::placeholders::_1)); + filter_info_topic_, + std::bind(&SpeedFilter::filterInfoCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); // Get global frame required for speed limit publisher global_frame_ = layered_costmap_->getGlobalFrameID(); // Create new speed limit publisher speed_limit_pub_ = node->create_publisher( - speed_limit_topic, rclcpp::QoS(10)); + speed_limit_topic); speed_limit_pub_->on_activate(); // Reset speed conversion states @@ -99,7 +100,7 @@ void SpeedFilter::filterInfoCallback( { std::lock_guard guard(*getMutex()); - rclcpp_lifecycle::LifecycleNode::SharedPtr node = node_.lock(); + nav2::LifecycleNode::SharedPtr node = node_.lock(); if (!node) { throw std::runtime_error{"Failed to lock node"}; } @@ -148,8 +149,9 @@ void SpeedFilter::filterInfoCallback( "SpeedFilter: Subscribing to \"%s\" topic for filter mask...", mask_topic_.c_str()); mask_sub_ = node->create_subscription( - mask_topic_, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&SpeedFilter::maskCallback, this, std::placeholders::_1)); + mask_topic_, + std::bind(&SpeedFilter::maskCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); } void SpeedFilter::maskCallback( diff --git a/nav2_costmap_2d/plugins/obstacle_layer.cpp b/nav2_costmap_2d/plugins/obstacle_layer.cpp index d4e2ccb9257..bac51b92f92 100644 --- a/nav2_costmap_2d/plugins/obstacle_layer.cpp +++ b/nav2_costmap_2d/plugins/obstacle_layer.cpp @@ -46,7 +46,6 @@ #include "pluginlib/class_list_macros.hpp" #include "sensor_msgs/point_cloud2_iterator.hpp" #include "nav2_costmap_2d/costmap_math.hpp" -#include "nav2_util/node_utils.hpp" #include "rclcpp/version.h" PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::ObstacleLayer, nav2_costmap_2d::Layer) @@ -101,7 +100,7 @@ void ObstacleLayer::onInitialize() node->get_parameter("track_unknown_space", track_unknown_space); node->get_parameter("transform_tolerance", transform_tolerance); node->get_parameter(name_ + "." + "observation_sources", topics_string); - double tf_filter_tolerance = nav2_util::declare_or_get_parameter(node, name_ + "." + + double tf_filter_tolerance = nav2::declare_or_get_parameter(node, name_ + "." + "tf_filter_tolerance", 0.05); int combination_method_param{}; @@ -230,7 +229,7 @@ void ObstacleLayer::onInitialize() source.c_str(), topic.c_str(), global_frame_.c_str(), expected_update_rate, observation_keep_time); - const auto custom_qos_profile = rclcpp::SensorDataQoS().keep_last(50); + const auto custom_qos_profile = nav2::qos::SensorDataQoS(50); // create a callback for the topic if (data_type == "LaserScan") { @@ -249,12 +248,15 @@ void ObstacleLayer::onInitialize() // For Jazzy compatibility in Message Filters API change #elif RCLCPP_VERSION_GTE(29, 0, 0) sub = std::make_shared>(node, topic, custom_qos_profile, sub_opt); + rclcpp_lifecycle::LifecycleNode>>( + std::static_pointer_cast(node), + topic, custom_qos_profile, sub_opt); // For Humble and Older compatibility in Message Filters API change #else sub = std::make_shared>( - node, topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt); + std::static_pointer_cast(node), + topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt); #endif sub->unsubscribe(); @@ -300,12 +302,15 @@ void ObstacleLayer::onInitialize() // For Jazzy compatibility in Message Filters API change #elif RCLCPP_VERSION_GTE(29, 0, 0) sub = std::make_shared>(node, topic, custom_qos_profile, sub_opt); + rclcpp_lifecycle::LifecycleNode>>( + std::static_pointer_cast(node), + topic, custom_qos_profile, sub_opt); // For Humble and Older compatibility in Message Filters API change #else sub = std::make_shared>( - node, topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt); + std::static_pointer_cast(node), + topic, custom_qos_profile.get_rmw_qos_profile(), sub_opt); #endif sub->unsubscribe(); diff --git a/nav2_costmap_2d/plugins/plugin_container_layer.cpp b/nav2_costmap_2d/plugins/plugin_container_layer.cpp index 9638b98ecf4..76f58b003ce 100644 --- a/nav2_costmap_2d/plugins/plugin_container_layer.cpp +++ b/nav2_costmap_2d/plugins/plugin_container_layer.cpp @@ -16,7 +16,7 @@ #include "nav2_costmap_2d/costmap_math.hpp" #include "nav2_costmap_2d/footprint.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "rclcpp/parameter_events_filter.hpp" #include "pluginlib/class_list_macros.hpp" @@ -35,11 +35,11 @@ void PluginContainerLayer::onInitialize() throw std::runtime_error{"Failed to lock node"}; } - nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "enabled", + nav2::declare_parameter_if_not_declared(node, name_ + "." + "enabled", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "plugins", + nav2::declare_parameter_if_not_declared(node, name_ + "." + "plugins", rclcpp::ParameterValue(std::vector{})); - nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "combination_method", + nav2::declare_parameter_if_not_declared(node, name_ + "." + "combination_method", rclcpp::ParameterValue(1)); node->get_parameter(name_ + "." + "enabled", enabled_); @@ -58,7 +58,7 @@ void PluginContainerLayer::onInitialize() plugin_types_.resize(plugin_names_.size()); for (unsigned int i = 0; i < plugin_names_.size(); ++i) { - plugin_types_[i] = nav2_util::get_plugin_type_param(node, name_ + "." + plugin_names_[i]); + plugin_types_[i] = nav2::get_plugin_type_param(node, name_ + "." + plugin_names_[i]); std::shared_ptr plugin = plugin_loader_.createSharedInstance(plugin_types_[i]); addPlugin(plugin, plugin_names_[i]); } diff --git a/nav2_costmap_2d/plugins/range_sensor_layer.cpp b/nav2_costmap_2d/plugins/range_sensor_layer.cpp index a7992726a98..6748ec5d2d1 100644 --- a/nav2_costmap_2d/plugins/range_sensor_layer.cpp +++ b/nav2_costmap_2d/plugins/range_sensor_layer.cpp @@ -152,9 +152,11 @@ void RangeSensorLayer::onInitialize() } range_subs_.push_back( node->create_subscription( - topic_name, rclcpp::SensorDataQoS(), std::bind( + topic_name, + std::bind( &RangeSensorLayer::bufferIncomingRangeMsg, this, - std::placeholders::_1))); + std::placeholders::_1), + nav2::qos::SensorDataQoS())); RCLCPP_INFO( logger_, "RangeSensorLayer: subscribed to " diff --git a/nav2_costmap_2d/plugins/static_layer.cpp b/nav2_costmap_2d/plugins/static_layer.cpp index 7e4aa7835bf..e4dbe277723 100644 --- a/nav2_costmap_2d/plugins/static_layer.cpp +++ b/nav2_costmap_2d/plugins/static_layer.cpp @@ -45,7 +45,7 @@ #include "pluginlib/class_list_macros.hpp" #include "tf2/convert.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" -#include "nav2_util/validate_messages.hpp" +#include "nav2_ros_common/validate_messages.hpp" PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::StaticLayer, nav2_costmap_2d::Layer) @@ -73,11 +73,9 @@ StaticLayer::onInitialize() getParameters(); - rclcpp::QoS map_qos(10); // initialize to default + rclcpp::QoS map_qos = nav2::qos::StandardTopicQoS(); // initialize to default if (map_subscribe_transient_local_) { - map_qos.transient_local(); - map_qos.reliable(); - map_qos.keep_last(1); + map_qos = nav2::qos::LatchedSubscriptionQoS(); } RCLCPP_INFO( @@ -92,14 +90,14 @@ StaticLayer::onInitialize() } map_sub_ = node->create_subscription( - map_topic_, map_qos, - std::bind(&StaticLayer::incomingMap, this, std::placeholders::_1)); + map_topic_, + std::bind(&StaticLayer::incomingMap, this, std::placeholders::_1), + map_qos); if (subscribe_to_updates_) { RCLCPP_INFO(logger_, "Subscribing to updates"); map_update_sub_ = node->create_subscription( map_topic_ + "_updates", - rclcpp::SystemDefaultsQoS(), std::bind(&StaticLayer::incomingUpdate, this, std::placeholders::_1)); } } @@ -280,7 +278,7 @@ StaticLayer::interpretValue(unsigned char value) void StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map) { - if (!nav2_util::validateMsg(*new_map)) { + if (!nav2::validateMsg(*new_map)) { RCLCPP_ERROR(logger_, "Received map message is malformed. Rejecting."); return; } diff --git a/nav2_costmap_2d/plugins/voxel_layer.cpp b/nav2_costmap_2d/plugins/voxel_layer.cpp index af1ac0a016f..4cf3face2ee 100644 --- a/nav2_costmap_2d/plugins/voxel_layer.cpp +++ b/nav2_costmap_2d/plugins/voxel_layer.cpp @@ -92,16 +92,14 @@ void VoxelLayer::onInitialize() node->get_parameter(name_ + "." + "combination_method", combination_method_param); combination_method_ = combination_method_from_int(combination_method_param); - auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(); - if (publish_voxel_) { voxel_pub_ = node->create_publisher( - "voxel_grid", custom_qos); + "voxel_grid", nav2::qos::LatchedPublisherQoS()); voxel_pub_->on_activate(); } clearing_endpoints_pub_ = node->create_publisher( - "clearing_endpoints", custom_qos); + "clearing_endpoints", nav2::qos::LatchedPublisherQoS()); clearing_endpoints_pub_->on_activate(); unknown_threshold_ += (VOXEL_BITS - size_z_); diff --git a/nav2_costmap_2d/src/clear_costmap_service.cpp b/nav2_costmap_2d/src/clear_costmap_service.cpp index b27b6841ddc..038fbb96311 100644 --- a/nav2_costmap_2d/src/clear_costmap_service.cpp +++ b/nav2_costmap_2d/src/clear_costmap_service.cpp @@ -32,7 +32,7 @@ using ClearAroundRobot = nav2_msgs::srv::ClearCostmapAroundRobot; using ClearEntirely = nav2_msgs::srv::ClearEntireCostmap; ClearCostmapService::ClearCostmapService( - const nav2_util::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, Costmap2DROS & costmap) : costmap_(costmap) { @@ -40,26 +40,20 @@ ClearCostmapService::ClearCostmapService( logger_ = node->get_logger(); reset_value_ = costmap_.getCostmap()->getDefaultValue(); - clear_except_service_ = std::make_shared>>( + clear_except_service_ = node->create_service( std::string("clear_except_") + costmap_.getName(), - node, std::bind( &ClearCostmapService::clearExceptRegionCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - clear_around_service_ = std::make_shared>>( + clear_around_service_ = node->create_service( std::string("clear_around_") + costmap_.getName(), - node, std::bind( &ClearCostmapService::clearAroundRobotCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - clear_entire_service_ = std::make_shared>>( + clear_entire_service_ = node->create_service( std::string("clear_entirely_") + costmap_.getName(), - node, std::bind( &ClearCostmapService::clearEntireCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); diff --git a/nav2_costmap_2d/src/costmap_2d_cloud.cpp b/nav2_costmap_2d/src/costmap_2d_cloud.cpp index d09e0a580f1..2dfe2bcb390 100644 --- a/nav2_costmap_2d/src/costmap_2d_cloud.cpp +++ b/nav2_costmap_2d/src/costmap_2d_cloud.cpp @@ -36,6 +36,7 @@ #include "nav2_voxel_grid/voxel_grid.hpp" #include "nav2_msgs/msg/voxel_grid.hpp" #include "nav2_util/execution_timer.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" static inline void mapToWorld3D( const unsigned int mx, @@ -218,11 +219,11 @@ int main(int argc, char ** argv) RCLCPP_DEBUG(g_node->get_logger(), "Starting up costmap_2d_cloud"); pub_marked = g_node->create_publisher( - "voxel_marked_cloud", 1); + "voxel_marked_cloud", nav2::qos::StandardTopicQoS()); pub_unknown = g_node->create_publisher( - "voxel_unknown_cloud", 1); + "voxel_unknown_cloud", nav2::qos::StandardTopicQoS()); auto sub = g_node->create_subscription( - "voxel_grid", rclcpp::SystemDefaultsQoS(), voxelCallback); + "voxel_grid", nav2::qos::StandardTopicQoS(), voxelCallback); rclcpp::spin(g_node->get_node_base_interface()); diff --git a/nav2_costmap_2d/src/costmap_2d_markers.cpp b/nav2_costmap_2d/src/costmap_2d_markers.cpp index 281150bbf28..0d4d3d5d3b1 100644 --- a/nav2_costmap_2d/src/costmap_2d_markers.cpp +++ b/nav2_costmap_2d/src/costmap_2d_markers.cpp @@ -46,6 +46,7 @@ #include "nav2_msgs/msg/voxel_grid.hpp" #include "nav2_voxel_grid/voxel_grid.hpp" #include "nav2_util/execution_timer.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" struct Cell { @@ -153,10 +154,10 @@ int main(int argc, char ** argv) RCLCPP_DEBUG(g_node->get_logger(), "Starting costmap_2d_marker"); pub = g_node->create_publisher( - "visualization_marker", 1); + "visualization_marker", nav2::qos::StandardTopicQoS()); auto sub = g_node->create_subscription( - "voxel_grid", rclcpp::SystemDefaultsQoS(), voxelCallback); + "voxel_grid", nav2::qos::StandardTopicQoS(), voxelCallback); rclcpp::spin(g_node->get_node_base_interface()); } diff --git a/nav2_costmap_2d/src/costmap_2d_publisher.cpp b/nav2_costmap_2d/src/costmap_2d_publisher.cpp index f7ee5a2c544..48f163b78af 100644 --- a/nav2_costmap_2d/src/costmap_2d_publisher.cpp +++ b/nav2_costmap_2d/src/costmap_2d_publisher.cpp @@ -50,7 +50,7 @@ namespace nav2_costmap_2d char * Costmap2DPublisher::cost_translation_table_ = NULL; Costmap2DPublisher::Costmap2DPublisher( - const nav2_util::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, Costmap2D * costmap, std::string global_frame, std::string topic_name, @@ -67,25 +67,21 @@ Costmap2DPublisher::Costmap2DPublisher( clock_ = node->get_clock(); logger_ = node->get_logger(); - auto custom_qos = rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(); - // TODO(bpwilcox): port onNewSubscription functionality for publisher costmap_pub_ = node->create_publisher( topic_name, - custom_qos); + nav2::qos::LatchedPublisherQoS()); costmap_raw_pub_ = node->create_publisher( topic_name + "_raw", - custom_qos); + nav2::qos::LatchedPublisherQoS()); costmap_update_pub_ = node->create_publisher( - topic_name + "_updates", custom_qos); + topic_name + "_updates", nav2::qos::LatchedPublisherQoS()); costmap_raw_update_pub_ = node->create_publisher( - topic_name + "_raw_updates", custom_qos); + topic_name + "_raw_updates", nav2::qos::LatchedPublisherQoS()); // Create a service that will use the callback function to handle requests. - costmap_service_ = std::make_shared>>( + costmap_service_ = node->create_service( std::string("get_") + topic_name, - node, std::bind( &Costmap2DPublisher::costmap_service_callback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 9c3edb21df6..01f49894a06 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -46,7 +46,7 @@ #include "nav2_costmap_2d/layered_costmap.hpp" #include "nav2_util/execution_timer.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2_ros/create_timer_ros.h" #include "nav2_util/robot_utils.hpp" @@ -59,7 +59,7 @@ using rcl_interfaces::msg::ParameterType; namespace nav2_costmap_2d { Costmap2DROS::Costmap2DROS(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("costmap", "", options), +: nav2::LifecycleNode("costmap", "", options), name_("costmap"), default_plugins_{"static_layer", "obstacle_layer", "inflation_layer"}, default_types_{ @@ -94,7 +94,7 @@ rclcpp::NodeOptions getChildNodeOptions( { std::vector new_arguments = parent_options.arguments(); replaceOrAddArgument(new_arguments, "-r", "__ns", - "__ns:=" + nav2_util::add_namespaces(parent_namespace, name)); + "__ns:=" + nav2::add_namespaces(parent_namespace, name)); replaceOrAddArgument(new_arguments, "-r", "__node", name + ":" + "__node:=" + name); replaceOrAddArgument(new_arguments, "-p", "use_sim_time", "use_sim_time:=" + std::string(use_sim_time ? "true" : "false")); @@ -106,11 +106,7 @@ Costmap2DROS::Costmap2DROS( const std::string & parent_namespace, const bool & use_sim_time, const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode(name, "", - // NodeOption arguments take precedence over the ones provided on the command line - // use this to make sure the node is placed on the provided namespace - // TODO(orduno) Pass a sub-node instead of creating a new node for better handling - // of the namespaces +: nav2::LifecycleNode(name, "", getChildNodeOptions(name, parent_namespace, use_sim_time, options) ), name_(name), @@ -158,7 +154,7 @@ Costmap2DROS::~Costmap2DROS() { } -nav2_util::CallbackReturn +nav2::CallbackReturn Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -167,7 +163,7 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) } catch (const std::exception & e) { RCLCPP_ERROR( get_logger(), "Failed to configure costmap! %s.", e.what()); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } callback_group_ = create_callback_group( @@ -203,14 +199,13 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) layered_costmap_->addPlugin(plugin); - // TODO(mjeronimo): instead of get(), use a shared ptr try { plugin->initialize(layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(), shared_from_this(), callback_group_); } catch (const std::exception & e) { RCLCPP_ERROR(get_logger(), "Failed to initialize costmap plugin %s! %s.", plugin_names_[i].c_str(), e.what()); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } lock.unlock(); @@ -240,11 +235,10 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) // Create the publishers and subscribers footprint_sub_ = create_subscription( "footprint", - rclcpp::SystemDefaultsQoS(), std::bind(&Costmap2DROS::setRobotFootprintPolygon, this, std::placeholders::_1)); footprint_pub_ = create_publisher( - "published_footprint", rclcpp::SystemDefaultsQoS()); + "published_footprint"); costmap_publisher_ = std::make_unique( shared_from_this(), @@ -275,10 +269,8 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) } // Service to get the cost at a point - get_cost_service_ = std::make_shared>>( + get_cost_service_ = create_service( std::string("get_cost_") + get_name(), - shared_from_this(), std::bind(&Costmap2DROS::getCostsCallback, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); @@ -287,11 +279,11 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/) executor_ = std::make_shared(); executor_->add_callback_group(callback_group_, get_node_base_interface()); - executor_thread_ = std::make_unique(executor_); - return nav2_util::CallbackReturn::SUCCESS; + executor_thread_ = std::make_unique(executor_); + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -323,7 +315,7 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/) "transform from %s to %s did not become available before timeout", get_name(), robot_base_frame_.c_str(), global_frame_.c_str()); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } // The error string will accumulate and errors will typically be the same, so the last @@ -353,10 +345,10 @@ Costmap2DROS::on_activate(const rclcpp_lifecycle::State & /*state*/) dyn_params_handler = this->add_on_set_parameters_callback( std::bind(&Costmap2DROS::dynamicParametersCallback, this, _1)); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -380,10 +372,10 @@ Costmap2DROS::on_deactivate(const rclcpp_lifecycle::State & /*state*/) layer_pub->on_deactivate(); } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -402,14 +394,14 @@ Costmap2DROS::on_cleanup(const rclcpp_lifecycle::State & /*state*/) footprint_sub_.reset(); footprint_pub_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn Costmap2DROS::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } void @@ -443,7 +435,7 @@ Costmap2DROS::getParameters() if (plugin_names_ == default_plugins_) { for (size_t i = 0; i < default_plugins_.size(); ++i) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_plugins_[i] + ".plugin", rclcpp::ParameterValue(default_types_[i])); } } @@ -452,10 +444,10 @@ Costmap2DROS::getParameters() // 1. All plugins must have 'plugin' param defined in their namespace to define the plugin type for (size_t i = 0; i < plugin_names_.size(); ++i) { - plugin_types_[i] = nav2_util::get_plugin_type_param(node, plugin_names_[i]); + plugin_types_[i] = nav2::get_plugin_type_param(node, plugin_names_[i]); } for (size_t i = 0; i < filter_names_.size(); ++i) { - filter_types_[i] = nav2_util::get_plugin_type_param(node, filter_names_[i]); + filter_types_[i] = nav2::get_plugin_type_param(node, filter_names_[i]); } // 2. The map publish frequency cannot be 0 (to avoid a divide-by-zero) diff --git a/nav2_costmap_2d/src/costmap_subscriber.cpp b/nav2_costmap_2d/src/costmap_subscriber.cpp index bdbc5e11ccb..0d4ff8f2069 100644 --- a/nav2_costmap_2d/src/costmap_subscriber.cpp +++ b/nav2_costmap_2d/src/costmap_subscriber.cpp @@ -21,42 +21,6 @@ namespace nav2_costmap_2d { -constexpr int costmapUpdateQueueDepth = 10; - -CostmapSubscriber::CostmapSubscriber( - const nav2_util::LifecycleNode::WeakPtr & parent, - const std::string & topic_name) -: topic_name_(topic_name) -{ - auto node = parent.lock(); - logger_ = node->get_logger(); - costmap_sub_ = node->create_subscription( - topic_name_, - rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1)); - costmap_update_sub_ = node->create_subscription( - topic_name_ + "_updates", - rclcpp::QoS(rclcpp::KeepLast(costmapUpdateQueueDepth)).transient_local().reliable(), - std::bind(&CostmapSubscriber::costmapUpdateCallback, this, std::placeholders::_1)); -} - -CostmapSubscriber::CostmapSubscriber( - const rclcpp::Node::WeakPtr & parent, - const std::string & topic_name) -: topic_name_(topic_name) -{ - auto node = parent.lock(); - logger_ = node->get_logger(); - costmap_sub_ = node->create_subscription( - topic_name_, - rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1)); - costmap_update_sub_ = node->create_subscription( - topic_name_ + "_updates", - rclcpp::QoS(rclcpp::KeepLast(costmapUpdateQueueDepth)).transient_local().reliable(), - std::bind(&CostmapSubscriber::costmapUpdateCallback, this, std::placeholders::_1)); -} - std::shared_ptr CostmapSubscriber::getCostmap() { if (!isCostmapReceived()) { diff --git a/nav2_costmap_2d/src/footprint_subscriber.cpp b/nav2_costmap_2d/src/footprint_subscriber.cpp index 7cd65781e27..138287571b0 100644 --- a/nav2_costmap_2d/src/footprint_subscriber.cpp +++ b/nav2_costmap_2d/src/footprint_subscriber.cpp @@ -25,38 +25,6 @@ namespace nav2_costmap_2d { -FootprintSubscriber::FootprintSubscriber( - const nav2_util::LifecycleNode::WeakPtr & parent, - const std::string & topic_name, - tf2_ros::Buffer & tf, - std::string robot_base_frame, - double transform_tolerance) -: tf_(tf), - robot_base_frame_(robot_base_frame), - transform_tolerance_(transform_tolerance) -{ - auto node = parent.lock(); - footprint_sub_ = node->create_subscription( - topic_name, rclcpp::SystemDefaultsQoS(), - std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1)); -} - -FootprintSubscriber::FootprintSubscriber( - const rclcpp::Node::WeakPtr & parent, - const std::string & topic_name, - tf2_ros::Buffer & tf, - std::string robot_base_frame, - double transform_tolerance) -: tf_(tf), - robot_base_frame_(robot_base_frame), - transform_tolerance_(transform_tolerance) -{ - auto node = parent.lock(); - footprint_sub_ = node->create_subscription( - topic_name, rclcpp::SystemDefaultsQoS(), - std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1)); -} - bool FootprintSubscriber::getFootprintRaw( std::vector & footprint, diff --git a/nav2_costmap_2d/src/layer.cpp b/nav2_costmap_2d/src/layer.cpp index dba276d0364..c0437974fe7 100644 --- a/nav2_costmap_2d/src/layer.cpp +++ b/nav2_costmap_2d/src/layer.cpp @@ -31,7 +31,7 @@ #include #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_costmap_2d { @@ -49,7 +49,7 @@ Layer::initialize( LayeredCostmap * parent, std::string name, tf2_ros::Buffer * tf, - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, rclcpp::CallbackGroup::SharedPtr callback_group) { layered_costmap_ = parent; @@ -82,7 +82,7 @@ Layer::declareParameter( throw std::runtime_error{"Failed to lock node"}; } local_params_.insert(param_name); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getFullName(param_name), value); } @@ -96,7 +96,7 @@ Layer::declareParameter( throw std::runtime_error{"Failed to lock node"}; } local_params_.insert(param_name); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getFullName(param_name), param_type); } diff --git a/nav2_costmap_2d/src/observation_buffer.cpp b/nav2_costmap_2d/src/observation_buffer.cpp index a3df54e080d..21d8c820bc9 100644 --- a/nav2_costmap_2d/src/observation_buffer.cpp +++ b/nav2_costmap_2d/src/observation_buffer.cpp @@ -49,7 +49,7 @@ using namespace std::chrono_literals; namespace nav2_costmap_2d { ObservationBuffer::ObservationBuffer( - const nav2_util::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string topic_name, double observation_keep_time, double expected_update_rate, diff --git a/nav2_costmap_2d/test/integration/costmap_tester.cpp b/nav2_costmap_2d/test/integration/costmap_tester.cpp index 66f80d11bb1..c7d44e6e70c 100644 --- a/nav2_costmap_2d/test/integration/costmap_tester.cpp +++ b/nav2_costmap_2d/test/integration/costmap_tester.cpp @@ -162,7 +162,7 @@ void testCallback() int main(int argc, char ** argv) { rclcpp::init(argc, argv); - auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); + auto node = nav2::LifecycleNode::make_shared("costmap_tester"); testing::InitGoogleTest(&argc, argv); tf_ = new tf2_ros::Buffer(node->get_clock()); diff --git a/nav2_costmap_2d/test/integration/dyn_params_tests.cpp b/nav2_costmap_2d/test/integration/dyn_params_tests.cpp index 87da2d52fc2..a543dda02ae 100644 --- a/nav2_costmap_2d/test/integration/dyn_params_tests.cpp +++ b/nav2_costmap_2d/test/integration/dyn_params_tests.cpp @@ -30,7 +30,7 @@ class DynParamTestNode TEST(DynParamTestNode, testDynParamsSet) { - auto node = std::make_shared("dyn_param_tester"); + auto node = std::make_shared("dyn_param_tester"); auto costmap = std::make_shared("test_costmap"); costmap->on_configure(rclcpp_lifecycle::State()); diff --git a/nav2_costmap_2d/test/integration/inflation_tests.cpp b/nav2_costmap_2d/test/integration/inflation_tests.cpp index 3cbf22336e8..19446c00e38 100644 --- a/nav2_costmap_2d/test/integration/inflation_tests.cpp +++ b/nav2_costmap_2d/test/integration/inflation_tests.cpp @@ -45,7 +45,7 @@ #include "nav2_costmap_2d/inflation_layer.hpp" #include "nav2_costmap_2d/observation_buffer.hpp" #include "../testing_helper.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" using geometry_msgs::msg::Point; @@ -74,7 +74,7 @@ class TestNode : public ::testing::Test void waitForMap(std::shared_ptr & slayer); protected: - nav2_util::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; }; std::vector TestNode::setRadii( @@ -171,7 +171,7 @@ void TestNode::initNode(std::vector parameters) auto options = rclcpp::NodeOptions(); options.parameter_overrides(parameters); - node_ = std::make_shared( + node_ = std::make_shared( "inflation_test_node", "", options); // Declare non-plugin specific costmap parameters diff --git a/nav2_costmap_2d/test/integration/obstacle_tests.cpp b/nav2_costmap_2d/test/integration/obstacle_tests.cpp index 56d422e678c..8a700f069fc 100644 --- a/nav2_costmap_2d/test/integration/obstacle_tests.cpp +++ b/nav2_costmap_2d/test/integration/obstacle_tests.cpp @@ -52,42 +52,42 @@ using std::none_of; using std::pair; using std::string; -class TestLifecycleNode : public nav2_util::LifecycleNode +class TestLifecycleNode : public nav2::LifecycleNode { public: explicit TestLifecycleNode(const string & name) - : nav2_util::LifecycleNode(name) + : nav2::LifecycleNode(name) { } - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onError(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onError(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } }; diff --git a/nav2_costmap_2d/test/integration/plugin_container_tests.cpp b/nav2_costmap_2d/test/integration/plugin_container_tests.cpp index 06e15ea6e6a..13969ae9a55 100644 --- a/nav2_costmap_2d/test/integration/plugin_container_tests.cpp +++ b/nav2_costmap_2d/test/integration/plugin_container_tests.cpp @@ -33,42 +33,42 @@ using std::none_of; using std::pair; using std::string; -class TestLifecycleNode : public nav2_util::LifecycleNode +class TestLifecycleNode : public nav2::LifecycleNode { public: explicit TestLifecycleNode(const string & name) - : nav2_util::LifecycleNode(name) + : nav2::LifecycleNode(name) { } - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onError(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onError(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } }; diff --git a/nav2_costmap_2d/test/integration/range_tests.cpp b/nav2_costmap_2d/test/integration/range_tests.cpp index 1a14113922f..30aba3f88f4 100644 --- a/nav2_costmap_2d/test/integration/range_tests.cpp +++ b/nav2_costmap_2d/test/integration/range_tests.cpp @@ -53,42 +53,42 @@ using std::none_of; using std::pair; using std::string; -class TestLifecycleNode : public nav2_util::LifecycleNode +class TestLifecycleNode : public nav2::LifecycleNode { public: explicit TestLifecycleNode(const string & name) - : nav2_util::LifecycleNode(name) + : nav2::LifecycleNode(name) { } - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onShutdown(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn onError(const rclcpp_lifecycle::State &) + nav2::CallbackReturn onError(const rclcpp_lifecycle::State &) { - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } }; diff --git a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp index a89d24a7da7..c0616176647 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_2d_publisher.cpp @@ -22,7 +22,7 @@ #include "tf2_ros/transform_listener.h" #include "nav2_costmap_2d/costmap_2d_ros.hpp" -class CostmapRosLifecycleNode : public nav2_util::LifecycleNode +class CostmapRosLifecycleNode : public nav2::LifecycleNode { public: explicit CostmapRosLifecycleNode(const std::string & name) @@ -31,71 +31,68 @@ class CostmapRosLifecycleNode : public nav2_util::LifecycleNode ~CostmapRosLifecycleNode() override = default; - nav2_util::CallbackReturn + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &) override { costmap_ros_ = std::make_shared( name_, std::string{get_namespace()}, get_parameter("use_sim_time").as_bool()); - costmap_thread_ = std::make_unique(costmap_ros_); + costmap_thread_ = std::make_unique(costmap_ros_); costmap_ros_->configure(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override { costmap_ros_->activate(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &) override { costmap_ros_->deactivate(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &) override { costmap_thread_.reset(); costmap_ros_->deactivate(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } protected: std::shared_ptr costmap_ros_; - std::unique_ptr costmap_thread_; + std::unique_ptr costmap_thread_; const std::string name_; }; class LayerSubscriber { public: - explicit LayerSubscriber(const nav2_util::LifecycleNode::WeakPtr & parent) + explicit LayerSubscriber(const nav2::LifecycleNode::WeakPtr & parent) { auto node = parent.lock(); callback_group_ = node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); - rclcpp::SubscriptionOptions sub_option; - sub_option.callback_group = callback_group_; - std::string topic_name = "/fake_costmap/static_layer_raw"; layer_sub_ = node->create_subscription( topic_name, - rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), std::bind(&LayerSubscriber::layerCallback, this, std::placeholders::_1), - sub_option); + nav2::qos::LatchedSubscriptionQoS(), + callback_group_); executor_ = std::make_shared(); executor_->add_callback_group(callback_group_, node->get_node_base_interface()); - executor_thread_ = std::make_unique(executor_); + executor_thread_ = std::make_unique(executor_); } ~LayerSubscriber() @@ -114,10 +111,10 @@ class LayerSubscriber } } - rclcpp::Subscription::SharedPtr layer_sub_; + nav2::Subscription::SharedPtr layer_sub_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; - std::unique_ptr executor_thread_; + std::unique_ptr executor_thread_; bool callback_hit_{false}; }; diff --git a/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp b/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp index 6fcabadd5f3..85468400224 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_subscriber.cpp @@ -24,23 +24,24 @@ class TestCostmapSubscriberShould : public ::testing::Test { public: TestCostmapSubscriberShould() - : topicName("/costmap"), node(nav2_util::LifecycleNode::make_shared("test_subscriber")) + : topicName("/costmap"), + node(std::make_shared("test_subscriber")) { dummyCostmapMsgSubscriber = node->create_subscription( - topicName, 10, + topicName, std::bind(&TestCostmapSubscriberShould::costmapCallback, this, std::placeholders::_1)); dummyCostmapRawMsgSubscriber = node->create_subscription( - topicName + "_raw", 10, + topicName + "_raw", std::bind(&TestCostmapSubscriberShould::costmapRawCallback, this, std::placeholders::_1)); dummyCostmapUpdateMsgSubscriber = node->create_subscription( - topicName + "_updates", 10, + topicName + "_updates", std::bind(&TestCostmapSubscriberShould::costmapUpdateCallback, this, std::placeholders::_1)); dummyCostmapRawUpdateMsgSubscriber = node->create_subscription( - topicName + "_raw_updates", 10, std::bind( + topicName + "_raw_updates", std::bind( &TestCostmapSubscriberShould::costmapRawUpdateCallback, this, std::placeholders::_1)); } @@ -180,17 +181,17 @@ class TestCostmapSubscriberShould : public ::testing::Test std::string topicName; char * cost_translation_table_ = NULL; - nav2_util::LifecycleNode::SharedPtr node; + nav2::LifecycleNode::SharedPtr node; rclcpp::Logger logger {rclcpp::get_logger("test_costmap_subscriber_should")}; std::unique_ptr costmapSubscriber; std::shared_ptr costmapToSend; std::vector> receivedGrids; - rclcpp::Subscription::SharedPtr dummyCostmapMsgSubscriber; - rclcpp::Subscription::SharedPtr dummyCostmapRawMsgSubscriber; - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr dummyCostmapMsgSubscriber; + nav2::Subscription::SharedPtr dummyCostmapRawMsgSubscriber; + nav2::Subscription::SharedPtr dummyCostmapUpdateMsgSubscriber; - rclcpp::Subscription::SharedPtr dummyCostmapRawUpdateMsgSubscriber; + nav2::Subscription::SharedPtr dummyCostmapRawUpdateMsgSubscriber; }; TEST_F(TestCostmapSubscriberShould, handleFullCostmapMsgs) diff --git a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp index 6fa648ddc8f..0bcb809c0dc 100644 --- a/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp +++ b/nav2_costmap_2d/test/integration/test_costmap_topic_collision_checker.cpp @@ -27,7 +27,7 @@ #include "nav2_costmap_2d/costmap_2d_publisher.hpp" #include "../testing_helper.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" @@ -47,7 +47,7 @@ class DummyCostmapSubscriber : public nav2_costmap_2d::CostmapSubscriber { public: DummyCostmapSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::string & topic_name) : CostmapSubscriber(node, topic_name) {} @@ -68,7 +68,7 @@ class DummyFootprintSubscriber : public nav2_costmap_2d::FootprintSubscriber { public: DummyFootprintSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::string & topic_name, tf2_ros::Buffer & tf) : FootprintSubscriber(node, topic_name, tf) @@ -81,7 +81,7 @@ class DummyFootprintSubscriber : public nav2_costmap_2d::FootprintSubscriber } }; -class TestCollisionChecker : public nav2_util::LifecycleNode +class TestCollisionChecker : public nav2::LifecycleNode { public: explicit TestCollisionChecker(std::string name) @@ -99,7 +99,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode declare_parameter("trinary_costmap", rclcpp::ParameterValue(true)); } - nav2_util::CallbackReturn + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -143,25 +143,25 @@ class TestCollisionChecker : public nav2_util::LifecycleNode executor_ = std::make_shared(); executor_->add_callback_group(callback_group_, get_node_base_interface()); - executor_thread_ = std::make_unique(executor_); - return nav2_util::CallbackReturn::SUCCESS; + executor_thread_ = std::make_unique(executor_); + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning Up"); @@ -174,7 +174,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode footprint_sub_.reset(); costmap_sub_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } ~TestCollisionChecker() {} @@ -284,7 +284,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; - std::unique_ptr executor_thread_; + std::unique_ptr executor_thread_; std::shared_ptr costmap_sub_; std::shared_ptr footprint_sub_; diff --git a/nav2_costmap_2d/test/testing_helper.hpp b/nav2_costmap_2d/test/testing_helper.hpp index 03e1d6a0bd8..bf15fb97d7a 100644 --- a/nav2_costmap_2d/test/testing_helper.hpp +++ b/nav2_costmap_2d/test/testing_helper.hpp @@ -28,7 +28,7 @@ #include "nav2_costmap_2d/obstacle_layer.hpp" #include "nav2_costmap_2d/inflation_layer.hpp" #include "nav2_costmap_2d/plugin_container_layer.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" const double MAX_Z(1.0); @@ -72,7 +72,7 @@ unsigned int countValues( void addStaticLayer( nav2_costmap_2d::LayeredCostmap & layers, - tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node, + tf2_ros::Buffer & tf, nav2::LifecycleNode::SharedPtr node, std::shared_ptr & slayer, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) { @@ -83,7 +83,7 @@ void addStaticLayer( void addObstacleLayer( nav2_costmap_2d::LayeredCostmap & layers, - tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node, + tf2_ros::Buffer & tf, nav2::LifecycleNode::SharedPtr node, std::shared_ptr & olayer, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) { @@ -94,7 +94,7 @@ void addObstacleLayer( void addRangeLayer( nav2_costmap_2d::LayeredCostmap & layers, - tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node, + tf2_ros::Buffer & tf, nav2::LifecycleNode::SharedPtr node, std::shared_ptr & rlayer, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) { @@ -134,7 +134,7 @@ void addObservation( void addInflationLayer( nav2_costmap_2d::LayeredCostmap & layers, - tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node, + tf2_ros::Buffer & tf, nav2::LifecycleNode::SharedPtr node, std::shared_ptr & ilayer, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) { @@ -146,7 +146,7 @@ void addInflationLayer( void addPluginContainerLayer( nav2_costmap_2d::LayeredCostmap & layers, - tf2_ros::Buffer & tf, nav2_util::LifecycleNode::SharedPtr node, + tf2_ros::Buffer & tf, nav2::LifecycleNode::SharedPtr node, std::shared_ptr & pclayer, std::string name, rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) diff --git a/nav2_costmap_2d/test/unit/binary_filter_test.cpp b/nav2_costmap_2d/test/unit/binary_filter_test.cpp index e1fda3bbbe1..f56d18b8278 100644 --- a/nav2_costmap_2d/test/unit/binary_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/binary_filter_test.cpp @@ -23,7 +23,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" #include "tf2_ros/transform_broadcaster.h" @@ -137,7 +137,7 @@ class BinaryStateSubscriber : public rclcpp::Node } private: - rclcpp::Subscription::SharedPtr subscriber_; + nav2::Subscription::SharedPtr subscriber_; std_msgs::msg::Bool::SharedPtr msg_; bool binary_state_updated_; }; // BinaryStateSubscriber @@ -248,7 +248,7 @@ class TestNode : public ::testing::Test const unsigned int height_ = 11; const double resolution_ = 1.0; - nav2_util::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; @@ -353,7 +353,7 @@ void TestNode::setDefaultState(bool default_state) bool TestNode::createBinaryFilter(const std::string & global_frame, double flip_threshold) { - node_ = std::make_shared("test_node"); + node_ = std::make_shared("test_node"); tf_buffer_ = std::make_shared(node_->get_clock()); tf_buffer_->setUsingDedicatedThread(true); // One-thread broadcasting-listening model tf_listener_ = std::make_shared(*tf_buffer_); diff --git a/nav2_costmap_2d/test/unit/costmap_cost_service_test.cpp b/nav2_costmap_2d/test/unit/costmap_cost_service_test.cpp index 3e82f51fcc9..1bfdfec6ee4 100644 --- a/nav2_costmap_2d/test/unit/costmap_cost_service_test.cpp +++ b/nav2_costmap_2d/test/unit/costmap_cost_service_test.cpp @@ -36,7 +36,7 @@ class GetCostServiceTest : public ::testing::Test } std::shared_ptr costmap_; - rclcpp::Client::SharedPtr client_; + nav2::ServiceClient::SharedPtr client_; }; TEST_F(GetCostServiceTest, TestWithoutFootprint) @@ -48,7 +48,7 @@ TEST_F(GetCostServiceTest, TestWithoutFootprint) request->poses.push_back(pose); request->use_footprint = false; - auto result_future = client_->async_send_request(request); + auto result_future = client_->async_call(request); if (rclcpp::spin_until_future_complete( costmap_, result_future) == rclcpp::FutureReturnCode::SUCCESS) @@ -73,7 +73,7 @@ TEST_F(GetCostServiceTest, TestWithFootprint) request->poses.push_back(pose); request->use_footprint = true; - auto result_future = client_->async_send_request(request); + auto result_future = client_->async_call(request); if (rclcpp::spin_until_future_complete( costmap_, result_future) == rclcpp::FutureReturnCode::SUCCESS) diff --git a/nav2_costmap_2d/test/unit/costmap_filter_service_test.cpp b/nav2_costmap_2d/test/unit/costmap_filter_service_test.cpp index 2047acbd13f..55774f0a2d6 100644 --- a/nav2_costmap_2d/test/unit/costmap_filter_service_test.cpp +++ b/nav2_costmap_2d/test/unit/costmap_filter_service_test.cpp @@ -17,9 +17,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" - +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_filters/costmap_filter.hpp" #include "std_srvs/srv/set_bool.hpp" @@ -45,7 +43,7 @@ class CostmapFilterWrapper : public nav2_costmap_2d::CostmapFilter name_ = name; } - void setNode(const nav2_util::LifecycleNode::WeakPtr & node) + void setNode(const nav2::LifecycleNode::WeakPtr & node) { node_ = node; } @@ -62,7 +60,7 @@ class TestNode : public ::testing::Test TestNode() { // Create new LifecycleNode - node_ = std::make_shared("test_node"); + node_ = std::make_shared("test_node"); // Create new CostmapFilter costmap_filter_ = std::make_shared(); @@ -84,11 +82,11 @@ class TestNode : public ::testing::Test template typename T::Response::SharedPtr send_request( - nav2_util::LifecycleNode::SharedPtr node, - typename rclcpp::Client::SharedPtr client, + nav2::LifecycleNode::SharedPtr node, + typename nav2::ServiceClient::SharedPtr client, typename T::Request::SharedPtr request) { - auto result = client->async_send_request(request); + auto result = client->async_call(request); // Wait for the result if (rclcpp::spin_until_future_complete(node, result) == rclcpp::FutureReturnCode::SUCCESS) { @@ -99,7 +97,7 @@ class TestNode : public ::testing::Test } protected: - nav2_util::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr costmap_filter_; }; diff --git a/nav2_costmap_2d/test/unit/declare_parameter_test.cpp b/nav2_costmap_2d/test/unit/declare_parameter_test.cpp index 4106936cef1..f6ee271fce2 100644 --- a/nav2_costmap_2d/test/unit/declare_parameter_test.cpp +++ b/nav2_costmap_2d/test/unit/declare_parameter_test.cpp @@ -31,8 +31,8 @@ class LayerWrapper : public nav2_costmap_2d::Layer TEST(DeclareParameter, useValidParameter) { LayerWrapper layer; - nav2_util::LifecycleNode::SharedPtr node = - std::make_shared("test_node"); + nav2::LifecycleNode::SharedPtr node = + std::make_shared("test_node"); tf2_ros::Buffer tf(node->get_clock()); nav2_costmap_2d::LayeredCostmap layers("frame", false, false); @@ -50,8 +50,8 @@ TEST(DeclareParameter, useValidParameter) TEST(DeclareParameter, useInvalidParameter) { LayerWrapper layer; - nav2_util::LifecycleNode::SharedPtr node = - std::make_shared("test_node"); + nav2::LifecycleNode::SharedPtr node = + std::make_shared("test_node"); tf2_ros::Buffer tf(node->get_clock()); nav2_costmap_2d::LayeredCostmap layers("frame", false, false); diff --git a/nav2_costmap_2d/test/unit/denoise_layer_test.cpp b/nav2_costmap_2d/test/unit/denoise_layer_test.cpp index 3f1a89cf212..c49a389b909 100644 --- a/nav2_costmap_2d/test/unit/denoise_layer_test.cpp +++ b/nav2_costmap_2d/test/unit/denoise_layer_test.cpp @@ -453,8 +453,8 @@ TEST_F(DenoiseLayerTester, updateCosts) { } std::shared_ptr constructLayer( - std::shared_ptr node = - std::make_shared("test_node")) + nav2::LifecycleNode::SharedPtr node = + std::make_shared("test_node")) { auto tf = std::make_shared(node->get_clock()); auto layers = std::make_shared("frame", false, false); @@ -480,7 +480,7 @@ TEST_F(DenoiseLayerTester, initializeDefault) { } TEST_F(DenoiseLayerTester, initializeCustom) { - auto node = std::make_shared("test_node"); + auto node = std::make_shared("test_node"); auto layer = constructLayer(node); node->set_parameter( rclcpp::Parameter(layer->getFullName("minimal_group_size"), rclcpp::ParameterValue(5))); @@ -495,7 +495,7 @@ TEST_F(DenoiseLayerTester, initializeCustom) { } TEST_F(DenoiseLayerTester, initializeInvalid) { - auto node = std::make_shared("test_node"); + auto node = std::make_shared("test_node"); auto layer = constructLayer(node); node->set_parameter( rclcpp::Parameter(layer->getFullName("minimal_group_size"), rclcpp::ParameterValue(-1))); diff --git a/nav2_costmap_2d/test/unit/keepout_filter_test.cpp b/nav2_costmap_2d/test/unit/keepout_filter_test.cpp index 4f8d1f21c92..413a423ce72 100644 --- a/nav2_costmap_2d/test/unit/keepout_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/keepout_filter_test.cpp @@ -21,7 +21,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" #include "tf2_ros/transform_broadcaster.h" @@ -119,7 +119,7 @@ class TestNode : public ::testing::Test std::vector keepout_points_; private: - nav2_util::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; @@ -208,7 +208,7 @@ void TestNode::waitSome(const std::chrono::nanoseconds & duration) void TestNode::createKeepoutFilter(const std::string & global_frame) { - node_ = std::make_shared("test_node"); + node_ = std::make_shared("test_node"); tf_buffer_ = std::make_shared(node_->get_clock()); tf_buffer_->setUsingDedicatedThread(true); // One-thread broadcasting-listening model tf_listener_ = std::make_shared(*tf_buffer_); diff --git a/nav2_costmap_2d/test/unit/speed_filter_test.cpp b/nav2_costmap_2d/test/unit/speed_filter_test.cpp index 2e1d2b4e8ca..0904ebd355c 100644 --- a/nav2_costmap_2d/test/unit/speed_filter_test.cpp +++ b/nav2_costmap_2d/test/unit/speed_filter_test.cpp @@ -23,7 +23,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" #include "tf2_ros/transform_broadcaster.h" @@ -135,7 +135,7 @@ class SpeedLimitSubscriber : public rclcpp::Node } private: - rclcpp::Subscription::SharedPtr subscriber_; + nav2::Subscription::SharedPtr subscriber_; nav2_msgs::msg::SpeedLimit::SharedPtr msg_; bool speed_limit_updated_; }; // SpeedLimitSubscriber @@ -243,7 +243,7 @@ class TestNode : public ::testing::Test const unsigned int height_ = 11; const double resolution_ = 1.0; - nav2_util::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_buffer_; std::shared_ptr tf_listener_; @@ -341,7 +341,7 @@ void TestNode::waitSome(const std::chrono::nanoseconds & duration) bool TestNode::createSpeedFilter(const std::string & global_frame) { - node_ = std::make_shared("test_node"); + node_ = std::make_shared("test_node"); tf_buffer_ = std::make_shared(node_->get_clock()); tf_buffer_->setUsingDedicatedThread(true); // One-thread broadcasting-listening model tf_listener_ = std::make_shared(*tf_buffer_); diff --git a/nav2_docking/opennav_docking/CMakeLists.txt b/nav2_docking/opennav_docking/CMakeLists.txt index 508091931b6..b1feb3e1d60 100644 --- a/nav2_docking/opennav_docking/CMakeLists.txt +++ b/nav2_docking/opennav_docking/CMakeLists.txt @@ -22,6 +22,8 @@ find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) find_package(yaml_cpp_vendor REQUIRED) find_package(yaml-cpp REQUIRED) +find_package(nav2_ros_common REQUIRED) +find_package(bond REQUIRED) nav2_package() @@ -35,6 +37,7 @@ target_include_directories(controller PUBLIC "$" "$" + "$" ) target_link_libraries(controller PUBLIC ${geometry_msgs_TARGETS} @@ -53,6 +56,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC angles::angles @@ -81,6 +85,7 @@ target_include_directories(pose_filter PUBLIC "$" "$" + "$" ) target_link_libraries(pose_filter PUBLIC ${geometry_msgs_TARGETS} @@ -97,6 +102,7 @@ target_include_directories(${executable_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${executable_name} PRIVATE ${library_name} rclcpp::rclcpp) @@ -109,9 +115,11 @@ target_include_directories(simple_charging_dock PUBLIC "$" "$" + "$" ) target_link_libraries(simple_charging_dock PUBLIC ${geometry_msgs_TARGETS} + ${bond_TARGETS} opennav_docking_core::opennav_docking_core pose_filter rclcpp::rclcpp @@ -119,6 +127,7 @@ target_link_libraries(simple_charging_dock PUBLIC ${sensor_msgs_TARGETS} tf2_geometry_msgs::tf2_geometry_msgs tf2_ros::tf2_ros + bondcpp::bondcpp ) target_link_libraries(simple_charging_dock PRIVATE angles::angles @@ -134,6 +143,7 @@ target_include_directories(simple_non_charging_dock PUBLIC "$" "$" + "$" ) target_link_libraries(simple_non_charging_dock PUBLIC ${geometry_msgs_TARGETS} @@ -193,6 +203,7 @@ ament_export_dependencies( nav2_util opennav_docking_core pluginlib + nav2_ros_common rclcpp rclcpp_action rclcpp_lifecycle diff --git a/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp b/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp index 90fb5cea38c..efb8f6ccf5b 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/controller.hpp @@ -27,7 +27,7 @@ #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp" #include "nav2_graceful_controller/smooth_control_law.hpp" #include "nav_msgs/msg/path.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace opennav_docking { @@ -47,7 +47,7 @@ class Controller * @param base_frame Robot base frame */ Controller( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr tf, + const nav2::LifecycleNode::SharedPtr & node, std::shared_ptr tf, std::string fixed_frame, std::string base_frame); /** @@ -108,7 +108,7 @@ class Controller * @param transform_tolerance Transform tolerance */ void configureCollisionChecker( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const nav2::LifecycleNode::SharedPtr & node, std::string costmap_topic, std::string footprint_topic, double transform_tolerance); // Dynamic parameters handler diff --git a/nav2_docking/opennav_docking/include/opennav_docking/dock_database.hpp b/nav2_docking/opennav_docking/include/opennav_docking/dock_database.hpp index d151992ea42..836417226d1 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/dock_database.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/dock_database.hpp @@ -23,10 +23,10 @@ #include "rclcpp/rclcpp.hpp" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/service_server.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/service_server.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/simple_action_server.hpp" #include "opennav_docking/utils.hpp" #include "opennav_docking/types.hpp" #include "nav2_msgs/srv/reload_dock_database.hpp" @@ -52,7 +52,7 @@ class DockDatabase * @return If successful */ bool initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::shared_ptr tf); + const nav2::LifecycleNode::WeakPtr & parent, std::shared_ptr tf); /** * @brief A destructor for opennav_docking::DockDatabase @@ -103,13 +103,13 @@ class DockDatabase * @return bool If successful */ bool getDockPlugins( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr tf); + const nav2::LifecycleNode::SharedPtr & node, std::shared_ptr tf); /** * @brief Populate database of dock instances * @param Node Node to get values from */ - bool getDockInstances(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node); + bool getDockInstances(const nav2::LifecycleNode::SharedPtr & node); /** * @brief Find a dock instance in the database from ID @@ -128,13 +128,12 @@ class DockDatabase const std::shared_ptr request, std::shared_ptr response); - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; std::shared_ptr mutex_; // Don't reload database while actively docking DockPluginMap dock_plugins_; DockMap dock_instances_; pluginlib::ClassLoader dock_loader_; - nav2_util::ServiceServer>::SharedPtr reload_db_service_; + nav2::ServiceServer::SharedPtr reload_db_service_; }; } // namespace opennav_docking diff --git a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp index 61edfc85888..06c6a7252e0 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/docking_server.hpp @@ -23,9 +23,9 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/simple_action_server.hpp" #include "nav2_util/twist_publisher.hpp" #include "nav_2d_utils/odom_subscriber.hpp" #include "opennav_docking/controller.hpp" @@ -42,11 +42,11 @@ namespace opennav_docking * @class opennav_docking::DockingServer * @brief An action server which implements charger docking node for AMRs */ -class DockingServer : public nav2_util::LifecycleNode +class DockingServer : public nav2::LifecycleNode { public: - using DockingActionServer = nav2_util::SimpleActionServer; - using UndockingActionServer = nav2_util::SimpleActionServer; + using DockingActionServer = nav2::SimpleActionServer; + using UndockingActionServer = nav2::SimpleActionServer; /** * @brief A constructor for opennav_docking::DockingServer @@ -146,7 +146,7 @@ class DockingServer : public nav2_util::LifecycleNode template void getPreemptedGoalIfRequested( typename std::shared_ptr goal, - const std::unique_ptr> & action_server); + const typename nav2::SimpleActionServer::SharedPtr & action_server); /** * @brief Checks and logs warning if action canceled @@ -156,7 +156,7 @@ class DockingServer : public nav2_util::LifecycleNode */ template bool checkAndWarnIfCancelled( - std::unique_ptr> & action_server, + typename nav2::SimpleActionServer::SharedPtr & action_server, const std::string & name); /** @@ -167,7 +167,7 @@ class DockingServer : public nav2_util::LifecycleNode */ template bool checkAndWarnIfPreempted( - std::unique_ptr> & action_server, + typename nav2::SimpleActionServer::SharedPtr & action_server, const std::string & name); /** @@ -175,35 +175,35 @@ class DockingServer : public nav2_util::LifecycleNode * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activate member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivate member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Reset member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in shutdown state * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** * @brief Publish zero velocity at terminal condition @@ -265,8 +265,8 @@ class DockingServer : public nav2_util::LifecycleNode std::unique_ptr vel_publisher_; std::unique_ptr odom_sub_; - std::unique_ptr docking_action_server_; - std::unique_ptr undocking_action_server_; + typename DockingActionServer::SharedPtr docking_action_server_; + typename UndockingActionServer::SharedPtr undocking_action_server_; std::unique_ptr dock_db_; std::unique_ptr navigator_; diff --git a/nav2_docking/opennav_docking/include/opennav_docking/navigator.hpp b/nav2_docking/opennav_docking/include/opennav_docking/navigator.hpp index f12b92883ea..3ced1d578a1 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/navigator.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/navigator.hpp @@ -26,7 +26,7 @@ #include "pluginlib/class_list_macros.hpp" #include "nav2_msgs/action/navigate_to_pose.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "opennav_docking/utils.hpp" #include "opennav_docking/types.hpp" @@ -40,13 +40,13 @@ class Navigator { public: using Nav2Pose = nav2_msgs::action::NavigateToPose; - using ActionClient = rclcpp_action::Client; + using ActionClient = nav2::ActionClient; /** * @brief A constructor for opennav_docking::Navigator * @param parent Weakptr to the node to use to get interances and parameters */ - explicit Navigator(const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent); + explicit Navigator(const nav2::LifecycleNode::WeakPtr & parent); /** * @brief A destructor for opennav_docking::Navigator @@ -79,7 +79,7 @@ class Navigator bool recursed = false); protected: - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor executor_; ActionClient::SharedPtr nav_to_pose_client_; diff --git a/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp b/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp index 65a5596c18c..719e6e5cf7d 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/simple_charging_dock.hpp @@ -24,6 +24,7 @@ #include "sensor_msgs/msg/joint_state.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "opennav_docking_core/charging_dock.hpp" #include "opennav_docking/pose_filter.hpp" @@ -47,7 +48,7 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock * @param tf A pointer to a TF buffer */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf); /** @@ -107,7 +108,7 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state); // Optionally subscribe to a detected dock pose topic - rclcpp::Subscription::SharedPtr dock_pose_sub_; + nav2::Subscription::SharedPtr dock_pose_sub_; rclcpp::Publisher::SharedPtr dock_pose_pub_; rclcpp::Publisher::SharedPtr filtered_dock_pose_pub_; rclcpp::Publisher::SharedPtr staging_pose_pub_; @@ -118,12 +119,12 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock geometry_msgs::msg::PoseStamped dock_pose_; // Subscribe to battery message, used to determine if charging - rclcpp::Subscription::SharedPtr battery_sub_; + nav2::Subscription::SharedPtr battery_sub_; bool is_charging_; bool use_battery_status_; // Optionally subscribe to joint state message, used to determine if stalled - rclcpp::Subscription::SharedPtr joint_state_sub_; + nav2::Subscription::SharedPtr joint_state_sub_; std::vector stall_joint_names_; double stall_velocity_threshold_, stall_effort_threshold_; bool is_stalled_; @@ -147,7 +148,7 @@ class SimpleChargingDock : public opennav_docking_core::ChargingDock double staging_x_offset_; double staging_yaw_offset_; - rclcpp_lifecycle::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf2_buffer_; }; diff --git a/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp b/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp index d037e1aa79c..a0b3a46531e 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/simple_non_charging_dock.hpp @@ -24,6 +24,7 @@ #include "sensor_msgs/msg/joint_state.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "opennav_docking_core/non_charging_dock.hpp" #include "opennav_docking/pose_filter.hpp" @@ -47,7 +48,7 @@ class SimpleNonChargingDock : public opennav_docking_core::NonChargingDock * @param tf A pointer to a TF buffer */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf); /** @@ -92,7 +93,7 @@ class SimpleNonChargingDock : public opennav_docking_core::NonChargingDock void jointStateCallback(const sensor_msgs::msg::JointState::SharedPtr state); // Optionally subscribe to a detected dock pose topic - rclcpp::Subscription::SharedPtr dock_pose_sub_; + nav2::Subscription::SharedPtr dock_pose_sub_; rclcpp::Publisher::SharedPtr dock_pose_pub_; rclcpp::Publisher::SharedPtr filtered_dock_pose_pub_; rclcpp::Publisher::SharedPtr staging_pose_pub_; @@ -103,7 +104,7 @@ class SimpleNonChargingDock : public opennav_docking_core::NonChargingDock geometry_msgs::msg::PoseStamped dock_pose_; // Optionally subscribe to joint state message, used to determine if stalled - rclcpp::Subscription::SharedPtr joint_state_sub_; + nav2::Subscription::SharedPtr joint_state_sub_; std::vector stall_joint_names_; double stall_velocity_threshold_, stall_effort_threshold_; bool is_stalled_; @@ -125,7 +126,7 @@ class SimpleNonChargingDock : public opennav_docking_core::NonChargingDock double staging_x_offset_; double staging_yaw_offset_; - rclcpp_lifecycle::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf2_buffer_; }; diff --git a/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp b/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp index d0b3dcdf379..69b5a72748e 100644 --- a/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp +++ b/nav2_docking/opennav_docking/include/opennav_docking/utils.hpp @@ -19,7 +19,7 @@ #include #include "yaml-cpp/yaml.h" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" #include "nav2_util/geometry_utils.hpp" #include "angles/angles.h" @@ -44,7 +44,7 @@ using opennav_docking_core::DockDirection; */ inline bool parseDockFile( const std::string & yaml_filepath, - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const nav2::LifecycleNode::SharedPtr & node, DockMap & dock_db) { YAML::Node yaml_file; @@ -116,7 +116,7 @@ inline bool parseDockFile( */ inline bool parseDockParams( const std::vector & docks_param, - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const nav2::LifecycleNode::SharedPtr & node, DockMap & dock_db) { Dock curr_dock; diff --git a/nav2_docking/opennav_docking/package.xml b/nav2_docking/opennav_docking/package.xml index 5e8b0070525..ecfa8082379 100644 --- a/nav2_docking/opennav_docking/package.xml +++ b/nav2_docking/opennav_docking/package.xml @@ -28,6 +28,7 @@ tf2_geometry_msgs tf2_ros yaml_cpp_vendor + nav2_ros_common ament_cmake_gtest ament_cmake_pytest diff --git a/nav2_docking/opennav_docking/src/controller.cpp b/nav2_docking/opennav_docking/src/controller.cpp index 62a87651bea..da1bab7f8aa 100644 --- a/nav2_docking/opennav_docking/src/controller.cpp +++ b/nav2_docking/opennav_docking/src/controller.cpp @@ -18,7 +18,7 @@ #include "rclcpp/rclcpp.hpp" #include "opennav_docking/controller.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav_2d_utils/conversions.hpp" #include "tf2/utils.hpp" @@ -26,48 +26,48 @@ namespace opennav_docking { Controller::Controller( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr tf, + const nav2::LifecycleNode::SharedPtr & node, std::shared_ptr tf, std::string fixed_frame, std::string base_frame) : tf2_buffer_(tf), fixed_frame_(fixed_frame), base_frame_(base_frame) { logger_ = node->get_logger(); clock_ = node->get_clock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.k_phi", rclcpp::ParameterValue(3.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.k_delta", rclcpp::ParameterValue(2.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.beta", rclcpp::ParameterValue(0.4)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.lambda", rclcpp::ParameterValue(2.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.v_linear_min", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.v_linear_max", rclcpp::ParameterValue(0.25)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.v_angular_max", rclcpp::ParameterValue(0.75)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.slowdown_radius", rclcpp::ParameterValue(0.25)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.rotate_to_heading_max_angular_accel", rclcpp::ParameterValue(3.2)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.use_collision_detection", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.costmap_topic", rclcpp::ParameterValue(std::string("local_costmap/costmap_raw"))); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.footprint_topic", rclcpp::ParameterValue( std::string("local_costmap/published_footprint"))); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.transform_tolerance", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.projection_time", rclcpp::ParameterValue(5.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3)); node->get_parameter("controller.k_phi", k_phi_); @@ -104,7 +104,7 @@ Controller::Controller( rotate_to_heading_max_angular_accel_); trajectory_pub_ = - node->create_publisher("docking_trajectory", 1); + node->create_publisher("docking_trajectory"); } Controller::~Controller() @@ -224,7 +224,7 @@ bool Controller::isTrajectoryCollisionFree( } void Controller::configureCollisionChecker( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const nav2::LifecycleNode::SharedPtr & node, std::string costmap_topic, std::string footprint_topic, double transform_tolerance) { costmap_sub_ = std::make_unique(node, costmap_topic); diff --git a/nav2_docking/opennav_docking/src/dock_database.cpp b/nav2_docking/opennav_docking/src/dock_database.cpp index 621cdd39f19..a8a88cfce33 100644 --- a/nav2_docking/opennav_docking/src/dock_database.cpp +++ b/nav2_docking/opennav_docking/src/dock_database.cpp @@ -30,7 +30,7 @@ DockDatabase::~DockDatabase() } bool DockDatabase::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::shared_ptr tf) { node_ = parent; @@ -55,10 +55,8 @@ bool DockDatabase::initialize( "Docking Server has %u dock types and %u dock instances available.", this->plugin_size(), this->instance_size()); - reload_db_service_ = std::make_shared>>( + reload_db_service_ = node->create_service( "~/reload_database", - node, std::bind( &DockDatabase::reloadDbCb, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); @@ -149,7 +147,7 @@ ChargingDock::Ptr DockDatabase::findDockPlugin(const std::string & type) } bool DockDatabase::getDockPlugins( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, + const nav2::LifecycleNode::SharedPtr & node, std::shared_ptr tf) { std::vector docks_plugins; @@ -168,7 +166,7 @@ bool DockDatabase::getDockPlugins( for (size_t i = 0; i != docks_plugins.size(); i++) { try { - std::string plugin_type = nav2_util::get_plugin_type_param( + std::string plugin_type = nav2::get_plugin_type_param( node, docks_plugins[i]); opennav_docking_core::ChargingDock::Ptr dock = dock_loader_.createUniqueInstance(plugin_type); @@ -188,7 +186,7 @@ bool DockDatabase::getDockPlugins( return true; } -bool DockDatabase::getDockInstances(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node) +bool DockDatabase::getDockInstances(const nav2::LifecycleNode::SharedPtr & node) { using rclcpp::ParameterType::PARAMETER_STRING; using rclcpp::ParameterType::PARAMETER_STRING_ARRAY; diff --git a/nav2_docking/opennav_docking/src/docking_server.cpp b/nav2_docking/opennav_docking/src/docking_server.cpp index c14686ee1a5..74f86be90ed 100644 --- a/nav2_docking/opennav_docking/src/docking_server.cpp +++ b/nav2_docking/opennav_docking/src/docking_server.cpp @@ -25,7 +25,7 @@ namespace opennav_docking { DockingServer::DockingServer(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("docking_server", "", options) +: nav2::LifecycleNode("docking_server", "", options) { RCLCPP_INFO(get_logger(), "Creating %s", get_name()); @@ -45,7 +45,7 @@ DockingServer::DockingServer(const rclcpp::NodeOptions & options) declare_parameter("rotation_angular_tolerance", 0.05); } -nav2_util::CallbackReturn +nav2::CallbackReturn DockingServer::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring %s", get_name()); @@ -77,7 +77,7 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state) } catch (rclcpp::exceptions::ParameterUninitializedException & ex) { } - vel_publisher_ = std::make_unique(node, "cmd_vel", 1); + vel_publisher_ = std::make_unique(node, "cmd_vel"); tf2_buffer_ = std::make_shared(node->get_clock()); // Create odom subscriber for backward blind docking @@ -86,14 +86,14 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state) odom_sub_ = std::make_unique(node, odom_topic); // Create the action servers for dock / undock - docking_action_server_ = std::make_unique( - node, "dock_robot", + docking_action_server_ = node->create_action_server( + "dock_robot", std::bind(&DockingServer::dockRobot, this), nullptr, std::chrono::milliseconds(500), true); - undocking_action_server_ = std::make_unique( - node, "undock_robot", + undocking_action_server_ = node->create_action_server( + "undock_robot", std::bind(&DockingServer::undockRobot, this), nullptr, std::chrono::milliseconds(500), true); @@ -105,13 +105,13 @@ DockingServer::on_configure(const rclcpp_lifecycle::State & state) dock_db_ = std::make_unique(mutex_); if (!dock_db_->initialize(node, tf2_buffer_)) { on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn DockingServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating %s", get_name()); @@ -133,10 +133,10 @@ DockingServer::on_activate(const rclcpp_lifecycle::State & /*state*/) // Create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn DockingServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating %s", get_name()); @@ -154,10 +154,10 @@ DockingServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // Destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn DockingServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up %s", get_name()); @@ -171,20 +171,20 @@ DockingServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) vel_publisher_.reset(); dock_backwards_.reset(); odom_sub_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn DockingServer::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down %s", get_name()); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } template void DockingServer::getPreemptedGoalIfRequested( typename std::shared_ptr goal, - const std::unique_ptr> & action_server) + const typename nav2::SimpleActionServer::SharedPtr & action_server) { if (action_server->is_preempt_requested()) { goal = action_server->accept_pending_goal(); @@ -193,7 +193,7 @@ void DockingServer::getPreemptedGoalIfRequested( template bool DockingServer::checkAndWarnIfCancelled( - std::unique_ptr> & action_server, + typename nav2::SimpleActionServer::SharedPtr & action_server, const std::string & name) { if (action_server->is_cancel_requested()) { @@ -205,7 +205,7 @@ bool DockingServer::checkAndWarnIfCancelled( template bool DockingServer::checkAndWarnIfPreempted( - std::unique_ptr> & action_server, + typename nav2::SimpleActionServer::SharedPtr & action_server, const std::string & name) { if (action_server->is_preempt_requested()) { @@ -230,12 +230,12 @@ void DockingServer::dockRobot() return; } - if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot")) { + if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot")) { docking_action_server_->terminate_all(); return; } - getPreemptedGoalIfRequested(goal, docking_action_server_); + getPreemptedGoalIfRequested(goal, docking_action_server_); Dock * dock{nullptr}; num_retries_ = 0; @@ -273,8 +273,8 @@ void DockingServer::dockRobot() RCLCPP_INFO(get_logger(), "Robot already within pre-staging pose tolerance for dock"); } else { std::function isPreempted = [this]() { - return checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || - checkAndWarnIfPreempted(docking_action_server_, "dock_robot"); + return checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || + checkAndWarnIfPreempted(docking_action_server_, "dock_robot"); }; navigator_->goToPose( @@ -434,8 +434,8 @@ void DockingServer::doInitialPerception(Dock * dock, geometry_msgs::msg::PoseSta throw opennav_docking_core::FailedToDetectDock("Failed initial dock detection"); } - if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || - checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) + if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || + checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) { return; } @@ -497,8 +497,8 @@ bool DockingServer::approachDock( } // Stop if cancelled/preempted - if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || - checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) + if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || + checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) { return false; } @@ -564,8 +564,8 @@ bool DockingServer::waitForCharge(Dock * dock) return true; } - if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || - checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) + if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || + checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) { return false; } @@ -589,8 +589,8 @@ bool DockingServer::resetApproach( publishDockingFeedback(DockRobot::Feedback::INITIAL_PERCEPTION); // Stop if cancelled/preempted - if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || - checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) + if (checkAndWarnIfCancelled(docking_action_server_, "dock_robot") || + checkAndWarnIfPreempted(docking_action_server_, "dock_robot")) { return false; } @@ -663,12 +663,12 @@ void DockingServer::undockRobot() return; } - if (checkAndWarnIfCancelled(undocking_action_server_, "undock_robot")) { + if (checkAndWarnIfCancelled(undocking_action_server_, "undock_robot")) { undocking_action_server_->terminate_all(result); return; } - getPreemptedGoalIfRequested(goal, undocking_action_server_); + getPreemptedGoalIfRequested(goal, undocking_action_server_); auto max_duration = rclcpp::Duration::from_seconds(goal->max_undocking_time); try { @@ -726,8 +726,8 @@ void DockingServer::undockRobot() } // Stop if cancelled/preempted - if (checkAndWarnIfCancelled(undocking_action_server_, "undock_robot") || - checkAndWarnIfPreempted(undocking_action_server_, "undock_robot")) + if (checkAndWarnIfCancelled(undocking_action_server_, "undock_robot") || + checkAndWarnIfPreempted(undocking_action_server_, "undock_robot")) { publishZeroVelocity(); undocking_action_server_->terminate_all(result); diff --git a/nav2_docking/opennav_docking/src/navigator.cpp b/nav2_docking/opennav_docking/src/navigator.cpp index ff76c5eecd7..c3c6a177685 100644 --- a/nav2_docking/opennav_docking/src/navigator.cpp +++ b/nav2_docking/opennav_docking/src/navigator.cpp @@ -20,11 +20,11 @@ namespace opennav_docking using namespace std::chrono_literals; // NOLINT -Navigator::Navigator(const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent) +Navigator::Navigator(const nav2::LifecycleNode::WeakPtr & parent) : node_(parent) { auto node = node_.lock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "navigator_bt_xml", rclcpp::ParameterValue(std::string(""))); node->get_parameter("navigator_bt_xml", navigator_bt_xml_); } @@ -37,11 +37,7 @@ void Navigator::activate() rclcpp::CallbackGroupType::MutuallyExclusive, false); executor_.add_callback_group(callback_group_, node->get_node_base_interface()); - nav_to_pose_client_ = rclcpp_action::create_client( - node->get_node_base_interface(), - node->get_node_graph_interface(), - node->get_node_logging_interface(), - node->get_node_waitables_interface(), + nav_to_pose_client_ = node->create_action_client( "navigate_to_pose", callback_group_); } diff --git a/nav2_docking/opennav_docking/src/simple_charging_dock.cpp b/nav2_docking/opennav_docking/src/simple_charging_dock.cpp index c11d3018a9e..ff8be965603 100644 --- a/nav2_docking/opennav_docking/src/simple_charging_dock.cpp +++ b/nav2_docking/opennav_docking/src/simple_charging_dock.cpp @@ -14,7 +14,7 @@ #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "opennav_docking/simple_charging_dock.hpp" #include "opennav_docking/utils.hpp" @@ -22,7 +22,7 @@ namespace opennav_docking { void SimpleChargingDock::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf) { name_ = name; @@ -34,55 +34,55 @@ void SimpleChargingDock::configure( } // Optionally use battery info to check when charging, else say charging if docked - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".use_battery_status", rclcpp::ParameterValue(true)); // Parameters for optional external detection of dock pose - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".use_external_detection_pose", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_timeout", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_translation_x", rclcpp::ParameterValue(-0.20)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_translation_y", rclcpp::ParameterValue(0.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_rotation_yaw", rclcpp::ParameterValue(0.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_rotation_pitch", rclcpp::ParameterValue(1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_rotation_roll", rclcpp::ParameterValue(-1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".filter_coef", rclcpp::ParameterValue(0.1)); // Charging threshold from BatteryState message - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".charging_threshold", rclcpp::ParameterValue(0.5)); // Optionally determine if docked via stall detection using joint_states - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".use_stall_detection", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".stall_joint_names", rclcpp::PARAMETER_STRING_ARRAY); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".stall_velocity_threshold", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".stall_effort_threshold", rclcpp::ParameterValue(1.0)); // If not using stall detection, this is how close robot should get to pose - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".docking_threshold", rclcpp::ParameterValue(0.05)); // Staging pose configuration - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".staging_x_offset", rclcpp::ParameterValue(-0.7)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".staging_yaw_offset", rclcpp::ParameterValue(0.0)); // Direction of docking and if we should rotate to dock - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".dock_direction", rclcpp::ParameterValue(std::string("forward"))); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".rotate_to_dock", rclcpp::ParameterValue(false)); node_->get_parameter(name + ".use_battery_status", use_battery_status_); @@ -125,19 +125,19 @@ void SimpleChargingDock::configure( if (use_battery_status_) { battery_sub_ = node_->create_subscription( - "battery_state", 1, + "battery_state", [this](const sensor_msgs::msg::BatteryState::SharedPtr state) { is_charging_ = state->current > charging_threshold_; - }); + }, nav2::qos::StandardTopicQoS()); } if (use_external_detection_pose_) { dock_pose_.header.stamp = rclcpp::Time(0); dock_pose_sub_ = node_->create_subscription( - "detected_dock_pose", 1, + "detected_dock_pose", [this](const geometry_msgs::msg::PoseStamped::SharedPtr pose) { detected_dock_pose_ = *pose; - }); + }, nav2::qos::StandardTopicQoS(1)); // Only want the most recent pose } bool use_stall_detection; @@ -149,14 +149,15 @@ void SimpleChargingDock::configure( RCLCPP_ERROR(node_->get_logger(), "stall_joint_names cannot be empty!"); } joint_state_sub_ = node_->create_subscription( - "joint_states", 1, - std::bind(&SimpleChargingDock::jointStateCallback, this, std::placeholders::_1)); + "joint_states", + std::bind(&SimpleChargingDock::jointStateCallback, this, std::placeholders::_1), + nav2::qos::StandardTopicQoS()); } - dock_pose_pub_ = node_->create_publisher("dock_pose", 1); + dock_pose_pub_ = node_->create_publisher("dock_pose"); filtered_dock_pose_pub_ = node_->create_publisher( - "filtered_dock_pose", 1); - staging_pose_pub_ = node_->create_publisher("staging_pose", 1); + "filtered_dock_pose"); + staging_pose_pub_ = node_->create_publisher("staging_pose"); } geometry_msgs::msg::PoseStamped SimpleChargingDock::getStagingPose( diff --git a/nav2_docking/opennav_docking/src/simple_non_charging_dock.cpp b/nav2_docking/opennav_docking/src/simple_non_charging_dock.cpp index 36b952b88ee..2a845559c6d 100644 --- a/nav2_docking/opennav_docking/src/simple_non_charging_dock.cpp +++ b/nav2_docking/opennav_docking/src/simple_non_charging_dock.cpp @@ -14,7 +14,7 @@ #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "opennav_docking/simple_non_charging_dock.hpp" #include "opennav_docking/utils.hpp" @@ -22,7 +22,7 @@ namespace opennav_docking { void SimpleNonChargingDock::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf) { name_ = name; @@ -33,47 +33,47 @@ void SimpleNonChargingDock::configure( } // Parameters for optional external detection of dock pose - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".use_external_detection_pose", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_timeout", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_translation_x", rclcpp::ParameterValue(-0.20)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_translation_y", rclcpp::ParameterValue(0.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_rotation_yaw", rclcpp::ParameterValue(0.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_rotation_pitch", rclcpp::ParameterValue(1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".external_detection_rotation_roll", rclcpp::ParameterValue(-1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".filter_coef", rclcpp::ParameterValue(0.1)); // Optionally determine if docked via stall detection using joint_states - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".use_stall_detection", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".stall_joint_names", rclcpp::PARAMETER_STRING_ARRAY); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".stall_velocity_threshold", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".stall_effort_threshold", rclcpp::ParameterValue(1.0)); // If not using stall detection, this is how close robot should get to pose - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".docking_threshold", rclcpp::ParameterValue(0.05)); // Staging pose configuration - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".staging_x_offset", rclcpp::ParameterValue(-0.7)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".staging_yaw_offset", rclcpp::ParameterValue(0.0)); // Direction of docking and if we should rotate to dock - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".dock_direction", rclcpp::ParameterValue(std::string("forward"))); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, name + ".rotate_to_dock", rclcpp::ParameterValue(false)); node_->get_parameter(name + ".use_external_detection_pose", use_external_detection_pose_); @@ -115,10 +115,10 @@ void SimpleNonChargingDock::configure( if (use_external_detection_pose_) { dock_pose_.header.stamp = rclcpp::Time(0); dock_pose_sub_ = node_->create_subscription( - "detected_dock_pose", 1, + "detected_dock_pose", [this](const geometry_msgs::msg::PoseStamped::SharedPtr pose) { detected_dock_pose_ = *pose; - }); + }, nav2::qos::StandardTopicQoS(1)); // Only want the most recent one } bool use_stall_detection; @@ -130,14 +130,15 @@ void SimpleNonChargingDock::configure( RCLCPP_ERROR(node_->get_logger(), "stall_joint_names cannot be empty!"); } joint_state_sub_ = node_->create_subscription( - "joint_states", 1, - std::bind(&SimpleNonChargingDock::jointStateCallback, this, std::placeholders::_1)); + "joint_states", + std::bind(&SimpleNonChargingDock::jointStateCallback, this, std::placeholders::_1), + nav2::qos::StandardTopicQoS()); } - dock_pose_pub_ = node_->create_publisher("dock_pose", 1); + dock_pose_pub_ = node_->create_publisher("dock_pose"); filtered_dock_pose_pub_ = node_->create_publisher( - "filtered_dock_pose", 1); - staging_pose_pub_ = node_->create_publisher("staging_pose", 1); + "filtered_dock_pose"); + staging_pose_pub_ = node_->create_publisher("staging_pose"); } geometry_msgs::msg::PoseStamped SimpleNonChargingDock::getStagingPose( diff --git a/nav2_docking/opennav_docking/test/CMakeLists.txt b/nav2_docking/opennav_docking/test/CMakeLists.txt index 149e401b9f6..60a045e09db 100644 --- a/nav2_docking/opennav_docking/test/CMakeLists.txt +++ b/nav2_docking/opennav_docking/test/CMakeLists.txt @@ -10,6 +10,12 @@ target_link_libraries(test_utils rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle ) +target_include_directories(test_utils + PUBLIC + "$" + "$" + "$" +) # Test dock database ament_add_gtest(test_dock_database @@ -21,6 +27,12 @@ target_link_libraries(test_dock_database rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle ) +target_include_directories(test_dock_database + PUBLIC + "$" + "$" + "$" +) # Test navigator ament_add_gtest(test_navigator @@ -35,6 +47,12 @@ target_link_libraries(test_navigator rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle ) +target_include_directories(test_navigator + PUBLIC + "$" + "$" + "$" +) # Test Controller ament_add_gtest(test_controller @@ -46,6 +64,12 @@ target_link_libraries(test_controller rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle ) +target_include_directories(test_controller + PUBLIC + "$" + "$" + "$" +) # Test Simple Dock ament_add_gtest(test_simple_charging_dock @@ -60,6 +84,12 @@ target_link_libraries(test_simple_charging_dock simple_charging_dock tf2_geometry_msgs::tf2_geometry_msgs ) +target_include_directories(test_simple_charging_dock + PUBLIC + "$" + "$" + "$" +) ament_add_gtest(test_simple_non_charging_dock test_simple_non_charging_dock.cpp ) @@ -72,6 +102,12 @@ target_link_libraries(test_simple_non_charging_dock target_link_libraries(test_simple_non_charging_dock ${library_name} simple_non_charging_dock ) +target_include_directories(test_simple_non_charging_dock + PUBLIC + "$" + "$" + "$" +) # Test Pose Filter (unit) ament_add_gtest(test_pose_filter @@ -84,21 +120,35 @@ target_link_libraries(test_pose_filter tf2::tf2 tf2_geometry_msgs::tf2_geometry_msgs ) +target_include_directories(test_pose_filter + PUBLIC + "$" + "$" + "$" +) # Test dock pluing for server tests add_library(test_dock SHARED testing_dock.cpp) target_link_libraries(test_dock PUBLIC ${geometry_msgs_TARGETS} + ${bond_TARGETS} opennav_docking_core::opennav_docking_core pluginlib::pluginlib rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros + bondcpp::bondcpp ) install(TARGETS test_dock ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION lib/${PROJECT_NAME} ) +target_include_directories(test_dock + PUBLIC + "$" + "$" + "$" +) ament_export_libraries(test_dock) # Test docking server (unit) @@ -112,6 +162,12 @@ target_link_libraries(test_docking_server_unit rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle ) +target_include_directories(test_docking_server_unit + PUBLIC + "$" + "$" + "$" +) # Test docking server (smoke) ament_add_pytest_test(test_docking_server_with_charging_dock test_docking_server.py diff --git a/nav2_docking/opennav_docking/test/test_controller.cpp b/nav2_docking/opennav_docking/test/test_controller.cpp index 587a588adfc..f0e982a919b 100644 --- a/nav2_docking/opennav_docking/test/test_controller.cpp +++ b/nav2_docking/opennav_docking/test/test_controller.cpp @@ -20,7 +20,7 @@ #include "opennav_docking/controller.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "tf2_ros/buffer.h" #include "ament_index_cpp/get_package_share_directory.hpp" @@ -34,7 +34,7 @@ class ControllerFixture : public opennav_docking::Controller { public: ControllerFixture( - const rclcpp_lifecycle::LifecycleNode::SharedPtr & node, std::shared_ptr tf, + const nav2::LifecycleNode::SharedPtr & node, std::shared_ptr tf, std::string fixed_frame, std::string base_frame) : Controller(node, tf, fixed_frame, base_frame) { @@ -55,7 +55,7 @@ class ControllerFixture : public opennav_docking::Controller } }; -class TestCollisionChecker : public nav2_util::LifecycleNode +class TestCollisionChecker : public nav2::LifecycleNode { public: explicit TestCollisionChecker(std::string name) @@ -69,7 +69,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode costmap_pub_.reset(); } - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & /*state*/) + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(this->get_logger(), "Configuring"); @@ -77,25 +77,27 @@ class TestCollisionChecker : public nav2_util::LifecycleNode footprint_pub_ = create_publisher( "test_footprint", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + footprint_pub_->on_activate(); costmap_pub_ = std::make_shared( shared_from_this(), costmap_.get(), "test_base_frame", "test_costmap", true); + costmap_pub_->on_activate(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(this->get_logger(), "Activating"); costmap_pub_->on_activate(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & /*state*/) + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(this->get_logger(), "Deactivating"); costmap_pub_->on_deactivate(); costmap_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } void publishFootprint( @@ -183,18 +185,19 @@ class TestCollisionChecker : public nav2_util::LifecycleNode private: std::shared_ptr costmap_; - rclcpp::Publisher::SharedPtr footprint_pub_; + nav2::Publisher::SharedPtr + footprint_pub_; std::shared_ptr costmap_pub_; }; TEST(ControllerTests, ObjectLifecycle) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model // Skip collision detection - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.use_collision_detection", rclcpp::ParameterValue(false)); auto controller = std::make_unique( @@ -208,7 +211,7 @@ TEST(ControllerTests, ObjectLifecycle) } TEST(ControllerTests, DynamicParameters) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto controller = std::make_unique( node, nullptr, "test_base_frame", "test_base_frame"); @@ -255,7 +258,7 @@ TEST(ControllerTests, DynamicParameters) { TEST(ControllerTests, TFException) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model @@ -269,19 +272,19 @@ TEST(ControllerTests, TFException) TEST(ControllerTests, CollisionCheckerDockForward) { auto collision_tester = std::make_shared("collision_test"); - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.projection_time", rclcpp::ParameterValue(10.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3)); auto controller = std::make_unique( @@ -334,19 +337,19 @@ TEST(ControllerTests, CollisionCheckerDockForward) { TEST(ControllerTests, CollisionCheckerDockBackward) { auto collision_tester = std::make_shared("collision_test"); - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.projection_time", rclcpp::ParameterValue(10.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3)); auto controller = std::make_unique( @@ -399,19 +402,19 @@ TEST(ControllerTests, CollisionCheckerDockBackward) { TEST(ControllerTests, CollisionCheckerUndockBackward) { auto collision_tester = std::make_shared("collision_test"); - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.projection_time", rclcpp::ParameterValue(10.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3)); auto controller = std::make_unique( @@ -472,19 +475,19 @@ TEST(ControllerTests, CollisionCheckerUndockBackward) { TEST(ControllerTests, CollisionCheckerUndockForward) { auto collision_tester = std::make_shared("collision_test"); - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); // One-thread broadcasting-listening model - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.footprint_topic", rclcpp::ParameterValue("test_footprint")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.costmap_topic", rclcpp::ParameterValue("test_costmap_raw")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.projection_time", rclcpp::ParameterValue(10.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.simulation_time_step", rclcpp::ParameterValue(0.1)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.dock_collision_threshold", rclcpp::ParameterValue(0.3)); auto controller = std::make_unique( @@ -543,14 +546,14 @@ TEST(ControllerTests, CollisionCheckerUndockForward) { } TEST(ControllerTests, RotateToHeading) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); float rotate_to_heading_angular_vel = 1.0; float rotate_to_heading_max_angular_accel = 3.2; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.rotate_to_heading_angular_vel", rclcpp::ParameterValue(rotate_to_heading_angular_vel)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "controller.rotate_to_heading_max_angular_accel", rclcpp::ParameterValue(rotate_to_heading_max_angular_accel)); diff --git a/nav2_docking/opennav_docking/test/test_dock_database.cpp b/nav2_docking/opennav_docking/test/test_dock_database.cpp index 73e0991fde3..df1dbde2e27 100644 --- a/nav2_docking/opennav_docking/test/test_dock_database.cpp +++ b/nav2_docking/opennav_docking/test/test_dock_database.cpp @@ -53,7 +53,7 @@ class DbShim : public opennav_docking::DockDatabase TEST(DatabaseTests, ObjectLifecycle) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); opennav_docking::DockDatabase db; db.initialize(node, nullptr); db.activate(); @@ -65,7 +65,7 @@ TEST(DatabaseTests, ObjectLifecycle) TEST(DatabaseTests, initializeBogusPlugins) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); std::vector plugins{"dockv1", "dockv2"}; node->declare_parameter("dock_plugins", rclcpp::ParameterValue(plugins)); opennav_docking::DockDatabase db; @@ -78,7 +78,7 @@ TEST(DatabaseTests, initializeBogusPlugins) TEST(DatabaseTests, findTests) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); DbShim db; db.populateOne(); @@ -93,7 +93,7 @@ TEST(DatabaseTests, findTests) TEST(DatabaseTests, getDockInstancesBadConversionFile) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); std::vector plugins{"dockv1"}; node->declare_parameter("dock_plugins", rclcpp::ParameterValue(plugins)); node->declare_parameter( @@ -115,7 +115,7 @@ TEST(DatabaseTests, getDockInstancesBadConversionFile) TEST(DatabaseTests, getDockInstancesWrongPath) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); std::vector plugins{"dockv1"}; node->declare_parameter("dock_plugins", rclcpp::ParameterValue(plugins)); node->declare_parameter( @@ -134,7 +134,7 @@ TEST(DatabaseTests, getDockInstancesWrongPath) TEST(DatabaseTests, reloadDbService) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); std::vector plugins{"dockv1"}; node->declare_parameter("dock_plugins", rclcpp::ParameterValue(plugins)); node->declare_parameter( @@ -151,7 +151,7 @@ TEST(DatabaseTests, reloadDbService) request->filepath = ament_index_cpp::get_package_share_directory("opennav_docking") + "/dock_files/test_dock_file.yaml"; EXPECT_TRUE(client->wait_for_service(1s)); - auto result = client->async_send_request(request); + auto result = client->async_call(request); EXPECT_EQ( rclcpp::spin_until_future_complete(node, result, 2s), rclcpp::FutureReturnCode::SUCCESS); @@ -162,7 +162,7 @@ TEST(DatabaseTests, reloadDbService) request2->filepath = ament_index_cpp::get_package_share_directory("opennav_docking") + "/file_does_not_exist.yaml"; EXPECT_TRUE(client->wait_for_service(1s)); - auto result2 = client->async_send_request(request2); + auto result2 = client->async_call(request2); EXPECT_EQ( rclcpp::spin_until_future_complete(node, result2, 2s), rclcpp::FutureReturnCode::SUCCESS); @@ -171,7 +171,7 @@ TEST(DatabaseTests, reloadDbService) TEST(DatabaseTests, reloadDbMutexLocked) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); std::vector plugins{"dockv1"}; node->declare_parameter("dock_plugins", rclcpp::ParameterValue(plugins)); node->declare_parameter( @@ -192,7 +192,7 @@ TEST(DatabaseTests, reloadDbMutexLocked) request->filepath = ament_index_cpp::get_package_share_directory("opennav_docking") + "/dock_files/test_dock_file.yaml"; EXPECT_TRUE(client->wait_for_service(1s)); - auto result = client->async_send_request(request); + auto result = client->async_call(request); EXPECT_EQ( rclcpp::spin_until_future_complete(node, result, 2s), rclcpp::FutureReturnCode::SUCCESS); diff --git a/nav2_docking/opennav_docking/test/test_docking_server_unit.cpp b/nav2_docking/opennav_docking/test/test_docking_server_unit.cpp index 755f6d28782..7cc1f2fe8ab 100644 --- a/nav2_docking/opennav_docking/test/test_docking_server_unit.cpp +++ b/nav2_docking/opennav_docking/test/test_docking_server_unit.cpp @@ -19,7 +19,7 @@ #include "geometry_msgs/msg/twist.hpp" #include "sensor_msgs/msg/battery_state.hpp" #include "opennav_docking/docking_server.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/node_thread.hpp" // Testing unit functions in docking server, smoke/system tests in python file @@ -60,7 +60,7 @@ TEST(DockingServerTests, ObjectLifecycle) TEST(DockingServerTests, testErrorExceptions) { auto node = std::make_shared(); - auto node_thread = nav2_util::NodeThread(node); + auto node_thread = nav2::NodeThread(node); auto node2 = std::make_shared("client_node"); // Setup 1 instance of the test failure dock & its plugin instance diff --git a/nav2_docking/opennav_docking/test/test_navigator.cpp b/nav2_docking/opennav_docking/test/test_navigator.cpp index 09f81494a79..6edb77db090 100644 --- a/nav2_docking/opennav_docking/test/test_navigator.cpp +++ b/nav2_docking/opennav_docking/test/test_navigator.cpp @@ -16,7 +16,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/simple_action_server.hpp" #include "opennav_docking/navigator.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" @@ -29,7 +29,7 @@ class DummyNavigationServer : rclcpp::Node { public: using ActionT = nav2_msgs::action::NavigateToPose; - using ActionServer = nav2_util::SimpleActionServer; + using ActionServer = nav2::SimpleActionServer; DummyNavigationServer() : Node("dummy_navigator") @@ -39,6 +39,7 @@ class DummyNavigationServer : rclcpp::Node get_node_clock_interface(), get_node_logging_interface(), get_node_waitables_interface(), + get_node_parameters_interface(), "navigate_to_pose", std::bind(&DummyNavigationServer::executeCallback, this), nullptr, std::chrono::milliseconds(500), true); @@ -83,7 +84,7 @@ class DummyNavigationServer : rclcpp::Node TEST(NavigatorTests, TestNavigatorReconfigure) { - auto node = std::make_shared("test_node"); + auto node = std::make_shared("test_node"); auto navigator = std::make_unique(node); node->configure(); node->activate(); @@ -106,7 +107,7 @@ TEST(NavigatorTests, TestNavigatorReconfigure) TEST(NavigatorTests, TestNavigator) { auto dummy_navigator_node = std::make_shared(); - auto node = std::make_shared("test_node"); + auto node = std::make_shared("test_node"); auto navigator = std::make_unique(node); navigator->activate(); diff --git a/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp b/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp index b88947dfd4c..293cfcc8933 100644 --- a/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp +++ b/nav2_docking/opennav_docking/test/test_simple_charging_dock.cpp @@ -41,7 +41,7 @@ class SimpleChargingDockShim : public opennav_docking::SimpleChargingDock TEST(SimpleChargingDockTests, ObjectLifecycle) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto dock = std::make_unique(); @@ -61,7 +61,7 @@ TEST(SimpleChargingDockTests, ObjectLifecycle) TEST(SimpleChargingDockTests, BatteryState) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto pub = node->create_publisher( "battery_state", rclcpp::QoS(1)); pub->on_activate(); @@ -103,7 +103,7 @@ TEST(SimpleChargingDockTests, BatteryState) TEST(SimpleChargingDockTests, StallDetection) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto pub = node->create_publisher( "joint_states", rclcpp::QoS(1)); pub->on_activate(); @@ -169,7 +169,7 @@ TEST(SimpleChargingDockTests, StallDetection) TEST(SimpleChargingDockTests, StagingPose) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto dock = std::make_unique(); dock->configure(node, "my_dock", nullptr); @@ -198,7 +198,7 @@ TEST(SimpleChargingDockTests, StagingPoseWithYawOffset) } ); - auto node = std::make_shared("test", options); + auto node = std::make_shared("test", "", options); auto dock = std::make_unique(); dock->configure(node, "my_dock", nullptr); @@ -220,7 +220,7 @@ TEST(SimpleChargingDockTests, StagingPoseWithYawOffset) TEST(SimpleChargingDockTests, RefinedPoseTest) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto pub = node->create_publisher( "detected_dock_pose", rclcpp::QoS(1)); @@ -256,7 +256,7 @@ TEST(SimpleChargingDockTests, RefinedPoseTest) TEST(SimpleChargingDockTests, RefinedPoseNotTransform) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto pub = node->create_publisher( "detected_dock_pose", rclcpp::QoS(1)); @@ -293,7 +293,7 @@ TEST(SimpleChargingDockTests, RefinedPoseNotTransform) TEST(SimpleChargingDockTests, IsDockedTransformException) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto pub = node->create_publisher( "detected_dock_pose", rclcpp::QoS(1)); @@ -337,7 +337,7 @@ TEST(SimpleChargingDockTests, IsDockedTransformException) TEST(SimpleChargingDockTests, GetDockDirection) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.dock_direction", rclcpp::ParameterValue("forward")); auto dock = std::make_unique(); @@ -365,7 +365,7 @@ TEST(SimpleChargingDockTests, GetDockDirection) TEST(SimpleChargingDockTests, ShouldRotateToDock) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); // Case 1: Direction to BACKWARD and rotate_to_dock to true node->declare_parameter("my_dock.dock_direction", rclcpp::ParameterValue("backward")); diff --git a/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp b/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp index eeee856d4a8..61d3207e150 100644 --- a/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp +++ b/nav2_docking/opennav_docking/test/test_simple_non_charging_dock.cpp @@ -41,7 +41,7 @@ class SimpleNonChargingDockShim : public opennav_docking::SimpleNonChargingDock TEST(SimpleNonChargingDockTests, ObjectLifecycle) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto dock = std::make_unique(); @@ -61,7 +61,7 @@ TEST(SimpleNonChargingDockTests, ObjectLifecycle) TEST(SimpleNonChargingDockTests, StallDetection) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto pub = node->create_publisher( "joint_states", rclcpp::QoS(1)); pub->on_activate(); @@ -130,7 +130,7 @@ TEST(SimpleNonChargingDockTests, StallDetection) TEST(SimpleNonChargingDockTests, StagingPose) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); auto dock = std::make_unique(); dock->configure(node, "my_dock", nullptr); @@ -159,7 +159,7 @@ TEST(SimpleNonChargingDockTests, StagingPoseWithYawOffset) } ); - auto node = std::make_shared("test", options); + auto node = std::make_shared("test", "", options); auto dock = std::make_unique(); dock->configure(node, "my_dock", nullptr); @@ -181,7 +181,7 @@ TEST(SimpleNonChargingDockTests, StagingPoseWithYawOffset) TEST(SimpleNonChargingDockTests, RefinedPoseTest) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto pub = node->create_publisher( "detected_dock_pose", rclcpp::QoS(1)); @@ -217,7 +217,7 @@ TEST(SimpleNonChargingDockTests, RefinedPoseTest) TEST(SimpleNonChargingDockTests, RefinedPoseNotTransform) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto pub = node->create_publisher( "detected_dock_pose", rclcpp::QoS(1)); @@ -254,7 +254,7 @@ TEST(SimpleNonChargingDockTests, RefinedPoseNotTransform) TEST(SimpleNonChargingDockTests, IsDockedTransformException) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.use_external_detection_pose", rclcpp::ParameterValue(true)); auto pub = node->create_publisher( "detected_dock_pose", rclcpp::QoS(1)); @@ -298,7 +298,7 @@ TEST(SimpleNonChargingDockTests, IsDockedTransformException) TEST(SimpleNonChargingDockTests, GetDockDirection) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("my_dock.dock_direction", rclcpp::ParameterValue("forward")); auto dock = std::make_unique(); @@ -326,7 +326,7 @@ TEST(SimpleNonChargingDockTests, GetDockDirection) TEST(SimpleChargingDockTests, ShouldRotateToDock) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); // Case 1: Direction to BACKWARD and rotate_to_dock to true node->declare_parameter("my_dock.dock_direction", rclcpp::ParameterValue("backward")); diff --git a/nav2_docking/opennav_docking/test/test_utils.cpp b/nav2_docking/opennav_docking/test/test_utils.cpp index 13bd363a55c..dfa0b12efd2 100644 --- a/nav2_docking/opennav_docking/test/test_utils.cpp +++ b/nav2_docking/opennav_docking/test/test_utils.cpp @@ -24,7 +24,7 @@ namespace opennav_docking TEST(UtilsTests, parseDockParams1) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); DockMap db; std::vector dock_str = {"dockA", "dockB"}; node->declare_parameter("docks", rclcpp::ParameterValue(dock_str)); @@ -38,7 +38,7 @@ TEST(UtilsTests, parseDockParams1) TEST(UtilsTests, parseDockParams2) { - auto node = std::make_shared("test2"); + auto node = std::make_shared("test2"); DockMap db; std::vector dock_str = {"dockC", "dockD"}; node->declare_parameter("docks", rclcpp::ParameterValue(dock_str)); @@ -70,7 +70,7 @@ TEST(UtilsTests, parseDockParams2) TEST(UtilsTests, parseDockParams3) { - auto node = std::make_shared("test3"); + auto node = std::make_shared("test3"); DockMap db; std::vector dock_str = {"dockE", "dockF"}; node->declare_parameter("docks", rclcpp::ParameterValue(dock_str)); @@ -89,7 +89,7 @@ TEST(UtilsTests, parseDockParams3) TEST(UtilsTests, parseDockFile) { - auto node = std::make_shared("test4"); + auto node = std::make_shared("test4"); DockMap db; std::string filepath = ament_index_cpp::get_package_share_directory("opennav_docking") + "/dock_files/test_dock_file.yaml"; @@ -111,7 +111,7 @@ TEST(UtilsTests, parseDockFile) TEST(UtilsTests, parseDockFile2) { - auto node = std::make_shared("test4"); + auto node = std::make_shared("test4"); DockMap db; // Test with a file that has no docks diff --git a/nav2_docking/opennav_docking/test/testing_dock.cpp b/nav2_docking/opennav_docking/test/testing_dock.cpp index a225291d804..8a33c3b3304 100644 --- a/nav2_docking/opennav_docking/test/testing_dock.cpp +++ b/nav2_docking/opennav_docking/test/testing_dock.cpp @@ -18,6 +18,7 @@ #include "opennav_docking_core/charging_dock.hpp" #include "opennav_docking_core/docking_exceptions.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace opennav_docking { @@ -31,7 +32,7 @@ class TestFailureDock : public opennav_docking_core::ChargingDock {} virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string &, std::shared_ptr) { node_ = parent.lock(); @@ -102,7 +103,7 @@ class TestFailureDock : public opennav_docking_core::ChargingDock } protected: - rclcpp_lifecycle::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; }; } // namespace opennav_docking diff --git a/nav2_docking/opennav_docking_bt/CMakeLists.txt b/nav2_docking/opennav_docking_bt/CMakeLists.txt index a852c4124b7..68998664cb7 100644 --- a/nav2_docking/opennav_docking_bt/CMakeLists.txt +++ b/nav2_docking/opennav_docking_bt/CMakeLists.txt @@ -12,6 +12,7 @@ find_package(nav2_util REQUIRED) find_package(nav_msgs REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_action REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -20,6 +21,7 @@ target_include_directories(opennav_dock_action_bt_node PUBLIC "$" "$" + "$" ) target_compile_definitions(opennav_dock_action_bt_node PRIVATE BT_PLUGIN_EXPORT) target_link_libraries(opennav_dock_action_bt_node PUBLIC @@ -34,6 +36,7 @@ target_include_directories(opennav_undock_action_bt_node PUBLIC "$" "$" + "$" ) target_compile_definitions(opennav_undock_action_bt_node PRIVATE BT_PLUGIN_EXPORT) target_link_libraries(opennav_undock_action_bt_node PUBLIC @@ -69,6 +72,7 @@ ament_export_dependencies( behaviortree_cpp geometry_msgs nav2_behavior_tree + nav2_ros_common nav2_msgs ) ament_export_targets(${PROJECT_NAME}) diff --git a/nav2_docking/opennav_docking_bt/package.xml b/nav2_docking/opennav_docking_bt/package.xml index d2071203bfe..3b946c8c296 100644 --- a/nav2_docking/opennav_docking_bt/package.xml +++ b/nav2_docking/opennav_docking_bt/package.xml @@ -19,6 +19,7 @@ nav_msgs rclcpp rclcpp_action + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_docking/opennav_docking_bt/test/test_dock_robot.cpp b/nav2_docking/opennav_docking_bt/test/test_dock_robot.cpp index a8250d269bf..bcdb71ba964 100644 --- a/nav2_docking/opennav_docking_bt/test/test_dock_robot.cpp +++ b/nav2_docking/opennav_docking_bt/test/test_dock_robot.cpp @@ -52,7 +52,7 @@ class DockRobotActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("dock_robot_action_test_fixture"); + node_ = std::make_shared("dock_robot_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -60,7 +60,7 @@ class DockRobotActionTestFixture : public ::testing::Test // Create the blackboard that will be shared by all of the nodes in the tree config_->blackboard = BT::Blackboard::create(); // Put items on the blackboard - config_->blackboard->set( + config_->blackboard->set( "node", node_); config_->blackboard->set( @@ -102,13 +102,13 @@ class DockRobotActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr DockRobotActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr DockRobotActionTestFixture::node_ = nullptr; std::shared_ptr DockRobotActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * DockRobotActionTestFixture::config_ = nullptr; diff --git a/nav2_docking/opennav_docking_bt/test/test_undock_robot.cpp b/nav2_docking/opennav_docking_bt/test/test_undock_robot.cpp index c2084d35f61..8b4fe31fede 100644 --- a/nav2_docking/opennav_docking_bt/test/test_undock_robot.cpp +++ b/nav2_docking/opennav_docking_bt/test/test_undock_robot.cpp @@ -52,7 +52,7 @@ class UndockRobotActionTestFixture : public ::testing::Test public: static void SetUpTestCase() { - node_ = std::make_shared("undock_robot_action_test_fixture"); + node_ = std::make_shared("undock_robot_action_test_fixture"); factory_ = std::make_shared(); config_ = new BT::NodeConfiguration(); @@ -60,7 +60,7 @@ class UndockRobotActionTestFixture : public ::testing::Test // Create the blackboard that will be shared by all of the nodes in the tree config_->blackboard = BT::Blackboard::create(); // Put items on the blackboard - config_->blackboard->set( + config_->blackboard->set( "node", node_); config_->blackboard->set( @@ -102,13 +102,13 @@ class UndockRobotActionTestFixture : public ::testing::Test static std::shared_ptr action_server_; protected: - static rclcpp::Node::SharedPtr node_; + static nav2::LifecycleNode::SharedPtr node_; static BT::NodeConfiguration * config_; static std::shared_ptr factory_; static std::shared_ptr tree_; }; -rclcpp::Node::SharedPtr UndockRobotActionTestFixture::node_ = nullptr; +nav2::LifecycleNode::SharedPtr UndockRobotActionTestFixture::node_ = nullptr; std::shared_ptr UndockRobotActionTestFixture::action_server_ = nullptr; BT::NodeConfiguration * UndockRobotActionTestFixture::config_ = nullptr; diff --git a/nav2_docking/opennav_docking_core/CMakeLists.txt b/nav2_docking/opennav_docking_core/CMakeLists.txt index 3d62476effc..7fb71cd761a 100644 --- a/nav2_docking/opennav_docking_core/CMakeLists.txt +++ b/nav2_docking/opennav_docking_core/CMakeLists.txt @@ -6,6 +6,7 @@ find_package(geometry_msgs REQUIRED) find_package(nav2_common REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -14,6 +15,7 @@ target_include_directories(opennav_docking_core INTERFACE "$" "$" + "$" ) target_link_libraries(opennav_docking_core INTERFACE ${geometry_msgs_TARGETS} @@ -43,6 +45,7 @@ ament_export_include_directories(include/${PROJECT_NAME}) ament_export_dependencies( geometry_msgs rclcpp_lifecycle + nav2_ros_common tf2_ros ) ament_export_targets(opennav_docking_core) diff --git a/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp b/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp index 8d4ace00eaa..a923cc98d26 100644 --- a/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp +++ b/nav2_docking/opennav_docking_core/include/opennav_docking_core/charging_dock.hpp @@ -18,7 +18,7 @@ #include #include -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "tf2_ros/buffer.h" @@ -52,7 +52,7 @@ class ChargingDock * @param tf A pointer to a TF buffer */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf) = 0; /** diff --git a/nav2_docking/opennav_docking_core/include/opennav_docking_core/non_charging_dock.hpp b/nav2_docking/opennav_docking_core/include/opennav_docking_core/non_charging_dock.hpp index c0efc0d0cc9..9422ee19f13 100644 --- a/nav2_docking/opennav_docking_core/include/opennav_docking_core/non_charging_dock.hpp +++ b/nav2_docking/opennav_docking_core/include/opennav_docking_core/non_charging_dock.hpp @@ -44,7 +44,7 @@ class NonChargingDock : public ChargingDock * @param tf A pointer to a TF buffer */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & name, std::shared_ptr tf) = 0; /** diff --git a/nav2_docking/opennav_docking_core/package.xml b/nav2_docking/opennav_docking_core/package.xml index 57a3d15b386..735f89cf24d 100644 --- a/nav2_docking/opennav_docking_core/package.xml +++ b/nav2_docking/opennav_docking_core/package.xml @@ -13,6 +13,7 @@ geometry_msgs rclcpp_lifecycle tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_dwb_controller/dwb_core/CMakeLists.txt b/nav2_dwb_controller/dwb_core/CMakeLists.txt index e689b318058..30637ca2a35 100644 --- a/nav2_dwb_controller/dwb_core/CMakeLists.txt +++ b/nav2_dwb_controller/dwb_core/CMakeLists.txt @@ -19,6 +19,7 @@ find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2_ros REQUIRED) find_package(visualization_msgs REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -31,6 +32,7 @@ add_library(dwb_core SHARED target_include_directories(dwb_core PUBLIC "$" "$" + "$" ) target_link_libraries(dwb_core PUBLIC ${builtin_interfaces_TARGETS} @@ -92,6 +94,7 @@ ament_export_dependencies( sensor_msgs tf2_ros visualization_msgs + nav2_ros_common ) ament_export_targets(dwb_core) diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp index 49290e8d94d..59b987f9cde 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp @@ -67,7 +67,7 @@ class DWBLocalPlanner : public nav2_core::Controller DWBLocalPlanner(); void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -217,7 +217,7 @@ class DWBLocalPlanner : public nav2_core::Controller */ virtual void loadCritics(); - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; rclcpp::Clock::SharedPtr clock_; rclcpp::Logger logger_{rclcpp::get_logger("DWBLocalPlanner")}; diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp index bd2b210e033..1e0c1b681de 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/publisher.hpp @@ -46,10 +46,10 @@ #include "rclcpp/rclcpp.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "visualization_msgs/msg/marker_array.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "builtin_interfaces/msg/duration.hpp" -using rclcpp_lifecycle::LifecyclePublisher; +using nav2::Publisher; namespace dwb_core { @@ -70,13 +70,13 @@ class DWBPublisher { public: explicit DWBPublisher( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name); - nav2_util::CallbackReturn on_configure(); - nav2_util::CallbackReturn on_activate(); - nav2_util::CallbackReturn on_deactivate(); - nav2_util::CallbackReturn on_cleanup(); + nav2::CallbackReturn on_configure(); + nav2::CallbackReturn on_activate(); + nav2::CallbackReturn on_deactivate(); + nav2::CallbackReturn on_cleanup(); /** * @brief Does the publisher require that the LocalPlanEvaluation be saved @@ -119,14 +119,14 @@ class DWBPublisher builtin_interfaces::msg::Duration marker_lifetime_; // Publisher Objects - std::shared_ptr> eval_pub_; - std::shared_ptr> global_pub_; - std::shared_ptr> transformed_pub_; - std::shared_ptr> local_pub_; - std::shared_ptr> marker_pub_; - std::shared_ptr> cost_grid_pc_pub_; - - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + std::shared_ptr> eval_pub_; + std::shared_ptr> global_pub_; + std::shared_ptr> transformed_pub_; + std::shared_ptr> local_pub_; + std::shared_ptr> marker_pub_; + std::shared_ptr> cost_grid_pc_pub_; + + nav2::LifecycleNode::WeakPtr node_; rclcpp::Clock::SharedPtr clock_; std::string plugin_name_; }; diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp index 17899a29947..080c598ed7f 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_critic.hpp @@ -47,7 +47,7 @@ #include "nav_2d_msgs/msg/path2_d.hpp" #include "dwb_msgs/msg/trajectory2_d.hpp" #include "sensor_msgs/msg/point_cloud.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace dwb_core { @@ -93,7 +93,7 @@ class TrajectoryCritic * @param costmap_ros Pointer to the costmap */ void initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & name, const std::string & ns, std::shared_ptr costmap_ros) @@ -182,7 +182,7 @@ class TrajectoryCritic std::string dwb_plugin_name_; std::shared_ptr costmap_ros_; double scale_; - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; }; } // namespace dwb_core diff --git a/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_generator.hpp b/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_generator.hpp index d918d61ddd2..a0922ef2f87 100644 --- a/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_generator.hpp +++ b/nav2_dwb_controller/dwb_core/include/dwb_core/trajectory_generator.hpp @@ -41,7 +41,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav_2d_msgs/msg/twist2_d.hpp" #include "dwb_msgs/msg/trajectory2_d.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace dwb_core { @@ -73,7 +73,7 @@ class TrajectoryGenerator * @param nh NodeHandle to read parameters from */ virtual void initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & plugin_name) = 0; virtual void reset() {} /** diff --git a/nav2_dwb_controller/dwb_core/package.xml b/nav2_dwb_controller/dwb_core/package.xml index 8b55d813004..bc5b42f2823 100644 --- a/nav2_dwb_controller/dwb_core/package.xml +++ b/nav2_dwb_controller/dwb_core/package.xml @@ -25,6 +25,7 @@ sensor_msgs tf2_ros visualization_msgs + nav2_ros_common ament_cmake_gtest ament_lint_common diff --git a/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp b/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp index 4f168a7d8df..0af32912024 100644 --- a/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp +++ b/nav2_dwb_controller/dwb_core/src/dwb_local_planner.cpp @@ -46,14 +46,14 @@ #include "nav_2d_utils/conversions.hpp" #include "nav_2d_utils/tf_help.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_core/controller_exceptions.hpp" #include "pluginlib/class_list_macros.hpp" #include "nav_msgs/msg/path.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using nav2_util::geometry_utils::euclidean_distance; namespace dwb_core @@ -66,7 +66,7 @@ DWBLocalPlanner::DWBLocalPlanner() } void DWBLocalPlanner::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) { diff --git a/nav2_dwb_controller/dwb_core/src/publisher.cpp b/nav2_dwb_controller/dwb_core/src/publisher.cpp index 7b860fef65a..aad8e2e16f2 100644 --- a/nav2_dwb_controller/dwb_core/src/publisher.cpp +++ b/nav2_dwb_controller/dwb_core/src/publisher.cpp @@ -42,20 +42,20 @@ #include "sensor_msgs/point_cloud2_iterator.hpp" #include "nav_2d_utils/conversions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "sensor_msgs/msg/point_cloud2.hpp" #include "visualization_msgs/msg/marker_array.hpp" #include "visualization_msgs/msg/marker.hpp" using std::max; using std::string; -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; namespace dwb_core { DWBPublisher::DWBPublisher( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) : node_(parent), plugin_name_(plugin_name) @@ -64,7 +64,7 @@ DWBPublisher::DWBPublisher( clock_ = node->get_clock(); } -nav2_util::CallbackReturn +nav2::CallbackReturn DWBPublisher::on_configure() { auto node = node_.lock(); @@ -101,21 +101,21 @@ DWBPublisher::on_configure() node->get_parameter(plugin_name_ + ".publish_trajectories", publish_trajectories_); node->get_parameter(plugin_name_ + ".publish_cost_grid_pc", publish_cost_grid_pc_); - eval_pub_ = node->create_publisher("evaluation", 1); - global_pub_ = node->create_publisher("received_global_plan", 1); - transformed_pub_ = node->create_publisher("transformed_global_plan", 1); - local_pub_ = node->create_publisher("local_plan", 1); - marker_pub_ = node->create_publisher("marker", 1); - cost_grid_pc_pub_ = node->create_publisher("cost_cloud", 1); + eval_pub_ = node->create_publisher("evaluation"); + global_pub_ = node->create_publisher("received_global_plan"); + transformed_pub_ = node->create_publisher("transformed_global_plan"); + local_pub_ = node->create_publisher("local_plan"); + marker_pub_ = node->create_publisher("marker"); + cost_grid_pc_pub_ = node->create_publisher("cost_cloud"); double marker_lifetime = 0.0; node->get_parameter(plugin_name_ + ".marker_lifetime", marker_lifetime); marker_lifetime_ = rclcpp::Duration::from_seconds(marker_lifetime); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn DWBPublisher::on_activate() { eval_pub_->on_activate(); @@ -125,10 +125,10 @@ DWBPublisher::on_activate() marker_pub_->on_activate(); cost_grid_pc_pub_->on_activate(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn DWBPublisher::on_deactivate() { eval_pub_->on_deactivate(); @@ -138,10 +138,10 @@ DWBPublisher::on_deactivate() marker_pub_->on_deactivate(); cost_grid_pc_pub_->on_deactivate(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn DWBPublisher::on_cleanup() { eval_pub_.reset(); @@ -151,7 +151,7 @@ DWBPublisher::on_cleanup() marker_pub_.reset(); cost_grid_pc_pub_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } void diff --git a/nav2_dwb_controller/dwb_critics/CMakeLists.txt b/nav2_dwb_controller/dwb_critics/CMakeLists.txt index 17833b75692..95f86354050 100644 --- a/nav2_dwb_controller/dwb_critics/CMakeLists.txt +++ b/nav2_dwb_controller/dwb_critics/CMakeLists.txt @@ -14,6 +14,7 @@ find_package(nav_2d_msgs REQUIRED) find_package(nav_2d_utils REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -34,6 +35,7 @@ add_library(${PROJECT_NAME} SHARED target_include_directories(${PROJECT_NAME} PUBLIC "$" "$" + "$" ) target_link_libraries(${PROJECT_NAME} PUBLIC costmap_queue::costmap_queue @@ -85,6 +87,7 @@ ament_export_dependencies( nav2_costmap_2d nav_2d_msgs rclcpp + nav2_ros_common ) ament_export_targets(${PROJECT_NAME}) diff --git a/nav2_dwb_controller/dwb_critics/package.xml b/nav2_dwb_controller/dwb_critics/package.xml index a697e486021..5e943e3fde2 100644 --- a/nav2_dwb_controller/dwb_critics/package.xml +++ b/nav2_dwb_controller/dwb_critics/package.xml @@ -20,6 +20,7 @@ nav_2d_utils pluginlib rclcpp + nav2_ros_common ament_cmake_gtest ament_lint_common diff --git a/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp b/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp index 2dfa3d415a7..5b14322cad1 100644 --- a/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp +++ b/nav2_dwb_controller/dwb_critics/src/base_obstacle.cpp @@ -39,7 +39,7 @@ #include "dwb_core/exceptions.hpp" #include "pluginlib/class_list_macros.hpp" #include "nav2_costmap_2d/cost_values.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" PLUGINLIB_EXPORT_CLASS(dwb_critics::BaseObstacleCritic, dwb_core::TrajectoryCritic) @@ -55,7 +55,7 @@ void BaseObstacleCritic::onInit() throw std::runtime_error{"Failed to lock node"}; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, dwb_plugin_name_ + "." + name_ + ".sum_scores", rclcpp::ParameterValue(false)); node->get_parameter(dwb_plugin_name_ + "." + name_ + ".sum_scores", sum_scores_); diff --git a/nav2_dwb_controller/dwb_critics/src/map_grid.cpp b/nav2_dwb_controller/dwb_critics/src/map_grid.cpp index 6dae0889da0..782ce618267 100644 --- a/nav2_dwb_controller/dwb_critics/src/map_grid.cpp +++ b/nav2_dwb_controller/dwb_critics/src/map_grid.cpp @@ -41,7 +41,7 @@ #include #include "dwb_core/exceptions.hpp" #include "nav2_costmap_2d/cost_values.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" using std::abs; using costmap_queue::CellData; @@ -68,7 +68,7 @@ void MapGridCritic::onInit() throw std::runtime_error{"Failed to lock node"}; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, dwb_plugin_name_ + "." + name_ + ".aggregation_type", rclcpp::ParameterValue(std::string("last"))); diff --git a/nav2_dwb_controller/dwb_critics/src/oscillation.cpp b/nav2_dwb_controller/dwb_critics/src/oscillation.cpp index 450f5b9751d..6472f5c1a23 100644 --- a/nav2_dwb_controller/dwb_critics/src/oscillation.cpp +++ b/nav2_dwb_controller/dwb_critics/src/oscillation.cpp @@ -38,7 +38,7 @@ #include #include #include "nav_2d_utils/parameters.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "dwb_core/exceptions.hpp" #include "pluginlib/class_list_macros.hpp" @@ -110,7 +110,7 @@ void OscillationCritic::onInit() node, dwb_plugin_name_ + "." + name_ + ".oscillation_reset_time", -1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, dwb_plugin_name_ + "." + name_ + ".x_only_threshold", rclcpp::ParameterValue(0.05)); diff --git a/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp b/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp index 53fdee4fd64..85ab2d41eec 100644 --- a/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp +++ b/nav2_dwb_controller/dwb_critics/src/prefer_forward.cpp @@ -35,11 +35,11 @@ #include "dwb_critics/prefer_forward.hpp" #include #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" PLUGINLIB_EXPORT_CLASS(dwb_critics::PreferForwardCritic, dwb_core::TrajectoryCritic) -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; namespace dwb_critics { diff --git a/nav2_dwb_controller/dwb_critics/test/base_obstacle_test.cpp b/nav2_dwb_controller/dwb_critics/test/base_obstacle_test.cpp index 15f5dd70a6e..11eb9b5a7b3 100644 --- a/nav2_dwb_controller/dwb_critics/test/base_obstacle_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/base_obstacle_test.cpp @@ -65,7 +65,7 @@ TEST(BaseObstacle, ScorePose) std::shared_ptr critic = std::make_shared(); - auto node = nav2_util::LifecycleNode::make_shared("base_obstacle_critic_tester"); + auto node = std::make_shared("base_obstacle_critic_tester"); auto costmap_ros = std::make_shared("test_global_costmap"); costmap_ros->configure(); @@ -124,7 +124,7 @@ TEST(BaseObstacle, CriticVisualization) std::shared_ptr critic = std::make_shared(); - auto node = nav2_util::LifecycleNode::make_shared("base_obstacle_critic_tester"); + auto node = std::make_shared("base_obstacle_critic_tester"); auto costmap_ros = std::make_shared("test_global_costmap"); costmap_ros->configure(); diff --git a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp index 92bbbcd870d..d8cee366909 100644 --- a/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/obstacle_footprint_test.cpp @@ -123,7 +123,7 @@ TEST(ObstacleFootprint, Prepare) std::shared_ptr critic = std::make_shared(); - auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); + auto node = std::make_shared("costmap_tester"); std::string ns = "/ns"; std::string costmap_name = "test_global_costmap"; @@ -185,7 +185,7 @@ TEST(ObstacleFootprint, PointCost) std::shared_ptr critic = std::make_shared(); - auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); + auto node = std::make_shared("costmap_tester"); std::string ns = "/ns"; std::string costmap_name = "test_global_costmap"; @@ -210,7 +210,7 @@ TEST(ObstacleFootprint, LineCost) std::shared_ptr critic = std::make_shared(); - auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); + auto node = std::make_shared("costmap_tester"); std::string ns = "/ns"; std::string costmap_name = "test_global_costmap"; diff --git a/nav2_dwb_controller/dwb_critics/test/prefer_forward_test.cpp b/nav2_dwb_controller/dwb_critics/test/prefer_forward_test.cpp index 460b5d04051..6ccf2c18a02 100644 --- a/nav2_dwb_controller/dwb_critics/test/prefer_forward_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/prefer_forward_test.cpp @@ -43,8 +43,8 @@ #include "rclcpp/rclcpp.hpp" #include "dwb_critics/prefer_forward.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" static constexpr double default_penalty = 1.0; static constexpr double default_strafe_x = 0.1; @@ -55,7 +55,7 @@ TEST(PreferForward, StartNode) { auto critic = std::make_shared(); auto costmap_ros = std::make_shared("test_global_costmap"); - auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); + auto node = std::make_shared("costmap_tester"); node->configure(); node->activate(); @@ -143,7 +143,7 @@ TEST(PreferForward, NoneDefaultValues) { auto critic = std::make_shared(); auto costmap_ros = std::make_shared("test_global_costmap"); - auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); + auto node = std::make_shared("costmap_tester"); node->configure(); node->activate(); @@ -155,16 +155,16 @@ TEST(PreferForward, NoneDefaultValues) std::string name = "test"; std::string ns = "ns"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, ns + "." + name + ".penalty", rclcpp::ParameterValue(penalty)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, ns + "." + name + ".strafe_x", rclcpp::ParameterValue(strafe_x)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, ns + "." + name + ".strafe_theta", rclcpp::ParameterValue(strafe_theta)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, ns + "." + name + ".theta_scale", rclcpp::ParameterValue(theta_scale)); diff --git a/nav2_dwb_controller/dwb_critics/test/twirling_test.cpp b/nav2_dwb_controller/dwb_critics/test/twirling_test.cpp index 949b1edc286..45d147f8e60 100644 --- a/nav2_dwb_controller/dwb_critics/test/twirling_test.cpp +++ b/nav2_dwb_controller/dwb_critics/test/twirling_test.cpp @@ -46,7 +46,7 @@ TEST(TwirlingTests, Scoring) std::shared_ptr critic = std::make_shared(); - auto node = nav2_util::LifecycleNode::make_shared("costmap_tester"); + auto node = std::make_shared("costmap_tester"); auto costmap_ros = std::make_shared("test_global_costmap"); costmap_ros->configure(); diff --git a/nav2_dwb_controller/dwb_plugins/CMakeLists.txt b/nav2_dwb_controller/dwb_plugins/CMakeLists.txt index 75a00b9b7f7..5624288e251 100644 --- a/nav2_dwb_controller/dwb_plugins/CMakeLists.txt +++ b/nav2_dwb_controller/dwb_plugins/CMakeLists.txt @@ -12,6 +12,7 @@ find_package(nav_2d_utils REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rcl_interfaces REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -23,6 +24,7 @@ add_library(standard_traj_generator SHARED target_include_directories(standard_traj_generator PUBLIC "$" "$" + "$" ) target_link_libraries(standard_traj_generator PUBLIC dwb_core::dwb_core @@ -75,6 +77,7 @@ ament_export_dependencies( nav_2d_msgs rclcpp rcl_interfaces + nav2_ros_common ) ament_export_targets(${PROJECT_NAME}) diff --git a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/kinematic_parameters.hpp b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/kinematic_parameters.hpp index d462e26f538..78062e1fd9a 100644 --- a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/kinematic_parameters.hpp +++ b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/kinematic_parameters.hpp @@ -40,7 +40,7 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" namespace dwb_plugins @@ -141,7 +141,7 @@ class KinematicsHandler public: KinematicsHandler(); ~KinematicsHandler(); - void initialize(const nav2_util::LifecycleNode::SharedPtr & nh, const std::string & plugin_name); + void initialize(const nav2::LifecycleNode::SharedPtr & nh, const std::string & plugin_name); inline KinematicParameters getKinematics() {return *kinematics_.load();} @@ -150,7 +150,7 @@ class KinematicsHandler using Ptr = std::shared_ptr; protected: - nav2_util::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; std::atomic kinematics_; // Dynamic parameters handler diff --git a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/limited_accel_generator.hpp b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/limited_accel_generator.hpp index 32bc24c4d68..cedb2d3f4b2 100644 --- a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/limited_accel_generator.hpp +++ b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/limited_accel_generator.hpp @@ -39,7 +39,7 @@ #include #include "dwb_plugins/standard_traj_generator.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace dwb_plugins { @@ -51,7 +51,7 @@ class LimitedAccelGenerator : public StandardTrajectoryGenerator { public: void initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & plugin_name) override; void startNewIteration(const nav_2d_msgs::msg::Twist2D & current_velocity) override; diff --git a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/standard_traj_generator.hpp b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/standard_traj_generator.hpp index db5467cd48d..4b2ce5828cd 100644 --- a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/standard_traj_generator.hpp +++ b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/standard_traj_generator.hpp @@ -43,7 +43,7 @@ #include "dwb_core/trajectory_generator.hpp" #include "dwb_plugins/velocity_iterator.hpp" #include "dwb_plugins/kinematic_parameters.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace dwb_plugins { @@ -57,7 +57,7 @@ class StandardTrajectoryGenerator : public dwb_core::TrajectoryGenerator public: // Standard TrajectoryGenerator interface void initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & plugin_name) override; void startNewIteration(const nav_2d_msgs::msg::Twist2D & current_velocity) override; bool hasMoreTwists() override; @@ -86,7 +86,7 @@ class StandardTrajectoryGenerator : public dwb_core::TrajectoryGenerator /** * @brief Initialize the VelocityIterator pointer. Put in its own function for easy overriding */ - virtual void initializeIterator(const nav2_util::LifecycleNode::SharedPtr & nh); + virtual void initializeIterator(const nav2::LifecycleNode::SharedPtr & nh); /** * @brief Calculate the velocity after a set period of time, given the desired velocity and acceleration limits diff --git a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp index e5feefc9faa..dd2c4af0f0e 100644 --- a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp +++ b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/velocity_iterator.hpp @@ -40,7 +40,7 @@ #include "nav_2d_msgs/msg/twist2_d.hpp" #include "dwb_plugins/kinematic_parameters.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace dwb_plugins { @@ -49,7 +49,7 @@ class VelocityIterator public: virtual ~VelocityIterator() {} virtual void initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, KinematicsHandler::Ptr kinematics, const std::string & plugin_name) = 0; virtual void startNewIteration(const nav_2d_msgs::msg::Twist2D & current_velocity, double dt) = 0; diff --git a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/xy_theta_iterator.hpp b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/xy_theta_iterator.hpp index 68ac9405c2f..545acbeae7d 100644 --- a/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/xy_theta_iterator.hpp +++ b/nav2_dwb_controller/dwb_plugins/include/dwb_plugins/xy_theta_iterator.hpp @@ -40,7 +40,7 @@ #include "dwb_plugins/velocity_iterator.hpp" #include "dwb_plugins/one_d_velocity_iterator.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace dwb_plugins { @@ -50,7 +50,7 @@ class XYThetaIterator : public VelocityIterator XYThetaIterator() : kinematics_handler_(nullptr), x_it_(nullptr), y_it_(nullptr), th_it_(nullptr) {} void initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, KinematicsHandler::Ptr kinematics, const std::string & plugin_name) override; void startNewIteration(const nav_2d_msgs::msg::Twist2D & current_velocity, double dt) override; diff --git a/nav2_dwb_controller/dwb_plugins/package.xml b/nav2_dwb_controller/dwb_plugins/package.xml index ba51d4d06e1..d848c166a1f 100644 --- a/nav2_dwb_controller/dwb_plugins/package.xml +++ b/nav2_dwb_controller/dwb_plugins/package.xml @@ -21,6 +21,7 @@ pluginlib rclcpp rcl_interfaces + nav2_ros_common ament_cmake_gtest ament_lint_common diff --git a/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp b/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp index d40f7f1b66e..dde49133011 100644 --- a/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/kinematic_parameters.cpp @@ -39,10 +39,10 @@ #include #include "nav_2d_utils/parameters.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_costmap_2d/costmap_filters/filter_values.hpp" -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using rcl_interfaces::msg::ParameterType; using std::placeholders::_1; @@ -65,7 +65,7 @@ KinematicsHandler::~KinematicsHandler() } void KinematicsHandler::initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & plugin_name) { node_ = nh; diff --git a/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp b/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp index 7591563370c..24d1c255973 100644 --- a/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/limited_accel_generator.cpp @@ -39,20 +39,20 @@ #include "nav_2d_utils/parameters.hpp" #include "pluginlib/class_list_macros.hpp" #include "dwb_core/exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace dwb_plugins { void LimitedAccelGenerator::initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & plugin_name) { plugin_name_ = plugin_name; StandardTrajectoryGenerator::initialize(nh, plugin_name_); try { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".sim_period", rclcpp::PARAMETER_DOUBLE); if (!nh->get_parameter(plugin_name + ".sim_period", acceleration_time_)) { // This actually should never appear, since declare_parameter_if_not_declared() diff --git a/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp b/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp index 3b57df08e1e..09024d3fbae 100644 --- a/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp @@ -41,13 +41,13 @@ #include "nav_2d_utils/parameters.hpp" #include "pluginlib/class_list_macros.hpp" #include "dwb_core/exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace dwb_plugins { void StandardTrajectoryGenerator::initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & plugin_name) { plugin_name_ = plugin_name; @@ -55,27 +55,27 @@ void StandardTrajectoryGenerator::initialize( kinematics_handler_->initialize(nh, plugin_name_); initializeIterator(nh); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".sim_time", rclcpp::ParameterValue(1.7)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".discretize_by_time", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".time_granularity", rclcpp::ParameterValue(0.5)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".linear_granularity", rclcpp::ParameterValue(0.5)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".angular_granularity", rclcpp::ParameterValue(0.025)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".include_last_point", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".limit_vel_cmd_in_traj", rclcpp::ParameterValue(false)); @@ -97,7 +97,7 @@ void StandardTrajectoryGenerator::initialize( } void StandardTrajectoryGenerator::initializeIterator( - const nav2_util::LifecycleNode::SharedPtr & nh) + const nav2::LifecycleNode::SharedPtr & nh) { velocity_iterator_ = std::make_shared(); velocity_iterator_->initialize(nh, kinematics_handler_, plugin_name_); diff --git a/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp b/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp index 5ca1992c6bc..c319bef4a72 100644 --- a/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp +++ b/nav2_dwb_controller/dwb_plugins/src/xy_theta_iterator.cpp @@ -39,24 +39,24 @@ #include #include "nav_2d_utils/parameters.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace dwb_plugins { void XYThetaIterator::initialize( - const nav2_util::LifecycleNode::SharedPtr & nh, + const nav2::LifecycleNode::SharedPtr & nh, KinematicsHandler::Ptr kinematics, const std::string & plugin_name) { kinematics_handler_ = kinematics; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".vx_samples", rclcpp::ParameterValue(20)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".vy_samples", rclcpp::ParameterValue(5)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, plugin_name + ".vtheta_samples", rclcpp::ParameterValue(20)); diff --git a/nav2_dwb_controller/dwb_plugins/test/kinematic_parameters_test.cpp b/nav2_dwb_controller/dwb_plugins/test/kinematic_parameters_test.cpp index a68fe691ba6..a63669d858b 100644 --- a/nav2_dwb_controller/dwb_plugins/test/kinematic_parameters_test.cpp +++ b/nav2_dwb_controller/dwb_plugins/test/kinematic_parameters_test.cpp @@ -55,7 +55,7 @@ class KinematicsHandlerTest : public dwb_plugins::KinematicsHandler TEST(KinematicParameters, SetAllParameters) { std::string nodeName = "test_node"; - auto node = nav2_util::LifecycleNode::make_shared(nodeName); + auto node = std::make_shared(nodeName); KinematicsHandlerTest kh; kh.initialize(node, nodeName); diff --git a/nav2_dwb_controller/dwb_plugins/test/speed_limit_test.cpp b/nav2_dwb_controller/dwb_plugins/test/speed_limit_test.cpp index ca102dae46a..1f1b583e6b6 100644 --- a/nav2_dwb_controller/dwb_plugins/test/speed_limit_test.cpp +++ b/nav2_dwb_controller/dwb_plugins/test/speed_limit_test.cpp @@ -41,7 +41,7 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_filters/filter_values.hpp" #include "dwb_plugins/kinematic_parameters.hpp" @@ -62,7 +62,7 @@ class TestNode : public ::testing::Test TestNode() { const std::string node_name = NODE_NAME; - node_ = nav2_util::LifecycleNode::make_shared(node_name); + node_ = std::make_shared(node_name); node_->declare_parameter( node_name + ".max_vel_x", rclcpp::ParameterValue(MAX_VEL_X)); @@ -88,7 +88,7 @@ class TestNode : public ::testing::Test ~TestNode() {} protected: - nav2_util::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; }; TEST_F(TestNode, TestPercentLimit) diff --git a/nav2_dwb_controller/dwb_plugins/test/twist_gen.cpp b/nav2_dwb_controller/dwb_plugins/test/twist_gen.cpp index 62f7c680ffa..6ac3c14cffd 100644 --- a/nav2_dwb_controller/dwb_plugins/test/twist_gen.cpp +++ b/nav2_dwb_controller/dwb_plugins/test/twist_gen.cpp @@ -41,7 +41,7 @@ #include "dwb_plugins/standard_traj_generator.hpp" #include "dwb_plugins/limited_accel_generator.hpp" #include "dwb_core/exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" using std::hypot; using std::fabs; @@ -83,7 +83,7 @@ std::vector getDefaultKinematicParameters() return parameters; } -rclcpp_lifecycle::LifecycleNode::SharedPtr makeTestNode( +nav2::LifecycleNode::SharedPtr makeTestNode( const std::string & name, const std::vector & overrides = {}) { @@ -92,7 +92,7 @@ rclcpp_lifecycle::LifecycleNode::SharedPtr makeTestNode( node_options.parameter_overrides().insert( node_options.parameter_overrides().end(), overrides.begin(), overrides.end()); - auto node = rclcpp_lifecycle::LifecycleNode::make_shared(name, node_options); + auto node = std::make_shared(name, "", node_options); node->on_configure(node->get_current_state()); node->on_activate(node->get_current_state()); diff --git a/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt b/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt index fd801fef661..a6aefd38e77 100644 --- a/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt +++ b/nav2_dwb_controller/nav_2d_utils/CMakeLists.txt @@ -12,6 +12,9 @@ find_package(rclcpp REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(bondcpp REQUIRED) nav2_package() @@ -21,6 +24,7 @@ target_include_directories(conversions PUBLIC "$" "$" + "$" ) target_link_libraries(conversions PUBLIC ${geometry_msgs_TARGETS} @@ -28,6 +32,7 @@ target_link_libraries(conversions PUBLIC ${nav_msgs_TARGETS} rclcpp::rclcpp tf2::tf2 + nav2_ros_common::nav2_ros_common ) target_link_libraries(conversions PRIVATE nav2_util::nav2_util_core @@ -40,6 +45,7 @@ target_include_directories(path_ops PUBLIC "$" "$" + "$" ) target_link_libraries(path_ops PUBLIC ${nav_2d_msgs_TARGETS} @@ -55,6 +61,7 @@ target_include_directories(tf_help PUBLIC "$" "$" + "$" ) target_link_libraries(tf_help PUBLIC conversions @@ -64,6 +71,8 @@ target_link_libraries(tf_help PUBLIC tf2::tf2 tf2_geometry_msgs::tf2_geometry_msgs tf2_ros::tf2_ros + rclcpp_lifecycle::rclcpp_lifecycle + rcl_lifecycle::rcl_lifecycle ) install(TARGETS conversions path_ops tf_help @@ -91,7 +100,18 @@ endif() ament_export_include_directories(include/${PROJECT_NAME}) ament_export_libraries(conversions path_ops tf_help) -ament_export_dependencies(geometry_msgs nav_2d_msgs nav_msgs rclcpp tf2 tf2_geometry_msgs tf2_ros) +ament_export_dependencies( + geometry_msgs + nav_2d_msgs + bondcpp + rclcpp_lifecycle + rcl_lifecycle + nav2_ros_common + nav_msgs + rclcpp + tf2 + tf2_geometry_msgs + tf2_ros) ament_export_targets(${PROJECT_NAME}) ament_package() diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp index 91f08b1bb50..2f989e71f2f 100644 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp +++ b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/odom_subscriber.hpp @@ -41,9 +41,9 @@ #include #include "nav_2d_msgs/msg/twist2_d_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav_2d_utils { @@ -62,10 +62,10 @@ class OdomSubscriber * @param default_topic Name of the topic that will be loaded of the odom_topic param is not set. */ explicit OdomSubscriber( - nav2_util::LifecycleNode::SharedPtr nh, + nav2::LifecycleNode::SharedPtr nh, std::string default_topic = "odom") { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, "odom_topic", rclcpp::ParameterValue(default_topic)); std::string odom_topic; @@ -73,7 +73,6 @@ class OdomSubscriber odom_sub_ = nh->create_subscription( odom_topic, - rclcpp::SystemDefaultsQoS(), std::bind(&OdomSubscriber::odomCallback, this, std::placeholders::_1)); } @@ -91,7 +90,7 @@ class OdomSubscriber odom_vel_.velocity.theta = msg->twist.twist.angular.z; } - rclcpp::Subscription::SharedPtr odom_sub_; + nav2::Subscription::SharedPtr odom_sub_; nav_2d_msgs::msg::Twist2DStamped odom_vel_; std::mutex odom_mutex_; }; diff --git a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp index 29a17532937..09b039487e0 100644 --- a/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp +++ b/nav2_dwb_controller/nav_2d_utils/include/nav_2d_utils/parameters.hpp @@ -39,8 +39,8 @@ #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" // TODO(crdelsey): Remove when code is re-enabled #pragma GCC diagnostic push @@ -61,10 +61,10 @@ namespace nav_2d_utils */ template param_t searchAndGetParam( - const nav2_util::LifecycleNode::SharedPtr & nh, const std::string & param_name, + const nav2::LifecycleNode::SharedPtr & nh, const std::string & param_name, const param_t & default_value) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( nh, param_name, rclcpp::ParameterValue(default_value)); return nh->get_parameter(param_name).get_value(); diff --git a/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp b/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp index c8424038a16..2a0ae9c7689 100644 --- a/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp +++ b/nav2_dwb_controller/nav_2d_utils/test/2d_utils_test.cpp @@ -38,8 +38,9 @@ #include "gtest/gtest.h" #include "nav_2d_utils/conversions.hpp" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/time.hpp" +#include "rclcpp_lifecycle/lifecycle_node.hpp" using nav_2d_utils::posesToPath; using nav_2d_utils::pathToPath; @@ -57,7 +58,7 @@ TEST(nav_2d_utils, PosesToPathNonEmpty) std::vector poses; geometry_msgs::msg::PoseStamped pose1; rclcpp::Time time1, time2; - auto node = rclcpp::Node::make_shared("twod_utils_test_node"); + auto node = std::make_shared("twod_utils_test_node"); time1 = node->now(); tf2::Quaternion quat1, quat2; diff --git a/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt b/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt index 3d9bd184177..5faa7c8daec 100644 --- a/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt +++ b/nav2_dwb_controller/nav_2d_utils/test/CMakeLists.txt @@ -1,5 +1,11 @@ ament_add_gtest(2d_utils_tests 2d_utils_test.cpp) target_link_libraries(2d_utils_tests conversions) +target_include_directories(2d_utils_tests + PUBLIC + "$" + "$" + "$" +) ament_add_gtest(path_ops_tests path_ops_test.cpp) target_link_libraries(path_ops_tests path_ops) diff --git a/nav2_graceful_controller/CMakeLists.txt b/nav2_graceful_controller/CMakeLists.txt index e79ea8d01fc..3a18bfa62ac 100644 --- a/nav2_graceful_controller/CMakeLists.txt +++ b/nav2_graceful_controller/CMakeLists.txt @@ -18,6 +18,7 @@ find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) find_package(visualization_msgs REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -27,6 +28,7 @@ target_include_directories(smooth_control_law PUBLIC "$" "$" + "$" ) target_link_libraries(smooth_control_law PUBLIC angles::angles @@ -48,6 +50,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -109,6 +112,7 @@ ament_export_dependencies( tf2 tf2_ros visualization_msgs + nav2_ros_common ) ament_export_targets(nav2_graceful_controller) diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp index 8669aafeedb..96358ae9607 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/graceful_controller.hpp @@ -60,7 +60,7 @@ class GracefulController : public nav2_core::Controller * @param costmap_ros Costmap2DROS object of environment */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -171,12 +171,10 @@ class GracefulController : public nav2_core::Controller // True from the time a new path arrives until we have completed an initial rotation bool do_initial_rotation_; - std::shared_ptr> transformed_plan_pub_; - std::shared_ptr> local_plan_pub_; - std::shared_ptr> - motion_target_pub_; - std::shared_ptr> - slowdown_pub_; + nav2::Publisher::SharedPtr transformed_plan_pub_; + nav2::Publisher::SharedPtr local_plan_pub_; + nav2::Publisher::SharedPtr motion_target_pub_; + nav2::Publisher::SharedPtr slowdown_pub_; std::unique_ptr path_handler_; std::unique_ptr param_handler_; std::unique_ptr control_law_; diff --git a/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp b/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp index 3d6ad16f33b..8d22841f817 100644 --- a/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp +++ b/nav2_graceful_controller/include/nav2_graceful_controller/parameter_handler.hpp @@ -21,11 +21,10 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" #include "nav2_util/odometry_utils.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_graceful_controller { @@ -67,7 +66,7 @@ class ParameterHandler * @brief Constructor for nav2_graceful_controller::ParameterHandler */ ParameterHandler( - rclcpp_lifecycle::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::string & plugin_name, rclcpp::Logger & logger, const double costmap_size_x); @@ -81,7 +80,7 @@ class ParameterHandler Parameters * getParams() {return ¶ms_;} protected: - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; /** * @brief Callback executed when a parameter change is detected diff --git a/nav2_graceful_controller/package.xml b/nav2_graceful_controller/package.xml index be7ee9c4806..a195e466bec 100644 --- a/nav2_graceful_controller/package.xml +++ b/nav2_graceful_controller/package.xml @@ -25,6 +25,7 @@ tf2_geometry_msgs tf2_ros visualization_msgs + nav2_ros_common ament_cmake_gtest ament_lint_auto diff --git a/nav2_graceful_controller/src/graceful_controller.cpp b/nav2_graceful_controller/src/graceful_controller.cpp index da880c7dc8e..fb0010698f4 100644 --- a/nav2_graceful_controller/src/graceful_controller.cpp +++ b/nav2_graceful_controller/src/graceful_controller.cpp @@ -25,11 +25,11 @@ namespace nav2_graceful_controller { void GracefulController::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, const std::shared_ptr tf, const std::shared_ptr costmap_ros) { - auto node = parent.lock(); + nav2::LifecycleNode::SharedPtr node = parent.lock(); if (!node) { throw nav2_core::ControllerException("Unable to lock node!"); } @@ -62,10 +62,10 @@ void GracefulController::configure( } // Publishers - transformed_plan_pub_ = node->create_publisher("transformed_global_plan", 1); - local_plan_pub_ = node->create_publisher("local_plan", 1); - motion_target_pub_ = node->create_publisher("motion_target", 1); - slowdown_pub_ = node->create_publisher("slowdown", 1); + transformed_plan_pub_ = node->create_publisher("transformed_global_plan"); + local_plan_pub_ = node->create_publisher("local_plan"); + motion_target_pub_ = node->create_publisher("motion_target"); + slowdown_pub_ = node->create_publisher("slowdown"); RCLCPP_INFO(logger_, "Configured Graceful Motion Controller: %s", plugin_name_.c_str()); } diff --git a/nav2_graceful_controller/src/parameter_handler.cpp b/nav2_graceful_controller/src/parameter_handler.cpp index 65fc260eb5f..95fdda9f82b 100644 --- a/nav2_graceful_controller/src/parameter_handler.cpp +++ b/nav2_graceful_controller/src/parameter_handler.cpp @@ -24,11 +24,11 @@ namespace nav2_graceful_controller { -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using rcl_interfaces::msg::ParameterType; ParameterHandler::ParameterHandler( - rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::string & plugin_name, + nav2::LifecycleNode::SharedPtr node, std::string & plugin_name, rclcpp::Logger & logger, const double costmap_size_x) { node_ = node; diff --git a/nav2_graceful_controller/src/path_handler.cpp b/nav2_graceful_controller/src/path_handler.cpp index b60df60436e..9dbfc291f8d 100644 --- a/nav2_graceful_controller/src/path_handler.cpp +++ b/nav2_graceful_controller/src/path_handler.cpp @@ -20,7 +20,7 @@ #include #include "nav2_core/controller_exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav_2d_utils/tf_help.hpp" #include "nav2_graceful_controller/path_handler.hpp" diff --git a/nav2_graceful_controller/test/test_graceful_controller.cpp b/nav2_graceful_controller/test/test_graceful_controller.cpp index 98e9dbd4e60..799daa8d8b3 100644 --- a/nav2_graceful_controller/test/test_graceful_controller.cpp +++ b/nav2_graceful_controller/test/test_graceful_controller.cpp @@ -15,7 +15,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_controller/plugins/simple_goal_checker.hpp" #include "nav2_core/controller_exceptions.hpp" #include "nav2_graceful_controller/ego_polar_coords.hpp" @@ -210,7 +210,7 @@ TEST(SmoothControlLawTest, calculateNextPose) { } TEST(GracefulControllerTest, configure) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); auto costmap_ros = std::make_shared("global_costmap"); @@ -235,20 +235,20 @@ TEST(GracefulControllerTest, configure) { } TEST(GracefulControllerTest, dynamicParameters) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); auto costmap_ros = std::make_shared("global_costmap"); // Set max search distant to negative so it warns - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.max_robot_pose_search_dist", rclcpp::ParameterValue(-2.0)); // Set initial rotation and allow backward to true so it warns and allow backward is false - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.initial_rotation", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.allow_backward", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.use_collision_detection", rclcpp::ParameterValue(true)); // Create controller @@ -344,7 +344,7 @@ TEST(GracefulControllerTest, dynamicParameters) { } TEST(GracefulControllerTest, createSlowdownMsg) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); auto costmap_ros = std::make_shared("global_costmap"); @@ -396,7 +396,7 @@ TEST(GracefulControllerTest, createSlowdownMsg) { } TEST(GracefulControllerTest, rotateToTarget) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); auto costmap_ros = std::make_shared("global_costmap"); @@ -447,7 +447,7 @@ TEST(GracefulControllerTest, rotateToTarget) { } TEST(GracefulControllerTest, setSpeedLimit) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); auto costmap_ros = std::make_shared("global_costmap"); @@ -491,7 +491,7 @@ TEST(GracefulControllerTest, setSpeedLimit) { } TEST(GracefulControllerTest, emptyPlan) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Create a costmap of 10x10 meters @@ -508,7 +508,7 @@ TEST(GracefulControllerTest, emptyPlan) { costmap_ros->on_configure(rclcpp_lifecycle::State()); // Set max search distant - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.max_robot_pose_search_dist", rclcpp::ParameterValue(5.0)); // Create controller @@ -542,7 +542,7 @@ TEST(GracefulControllerTest, emptyPlan) { } TEST(GracefulControllerTest, poseOutsideCostmap) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Create a costmap of 10x10 meters @@ -559,7 +559,7 @@ TEST(GracefulControllerTest, poseOutsideCostmap) { costmap_ros->on_configure(rclcpp_lifecycle::State()); // Set max search distant - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.max_robot_pose_search_dist", rclcpp::ParameterValue(5.0)); // Create controller @@ -597,7 +597,7 @@ TEST(GracefulControllerTest, poseOutsideCostmap) { } TEST(GracefulControllerTest, noPruningPlan) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Create a costmap of 10x10 meters @@ -614,7 +614,7 @@ TEST(GracefulControllerTest, noPruningPlan) { costmap_ros->on_configure(rclcpp_lifecycle::State()); // Set max search distant - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.max_robot_pose_search_dist", rclcpp::ParameterValue(5.0)); // Create controller @@ -663,7 +663,7 @@ TEST(GracefulControllerTest, noPruningPlan) { } TEST(GracefulControllerTest, pruningPlan) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Create a costmap of 20x20 meters @@ -680,7 +680,7 @@ TEST(GracefulControllerTest, pruningPlan) { costmap_ros->on_configure(rclcpp_lifecycle::State()); // Set max search distant - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.max_robot_pose_search_dist", rclcpp::ParameterValue(9.0)); // Create controller @@ -740,7 +740,7 @@ TEST(GracefulControllerTest, pruningPlan) { } TEST(GracefulControllerTest, pruningPlanOutsideCostmap) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Create a costmap of 10x10 meters @@ -757,7 +757,7 @@ TEST(GracefulControllerTest, pruningPlanOutsideCostmap) { costmap_ros->on_configure(rclcpp_lifecycle::State()); // Set max search distant - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.max_robot_pose_search_dist", rclcpp::ParameterValue(15.0)); // Create controller @@ -806,12 +806,12 @@ TEST(GracefulControllerTest, pruningPlanOutsideCostmap) { } TEST(GracefulControllerTest, computeVelocityCommandRotate) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.v_angular_max", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.rotation_scaling_factor", rclcpp::ParameterValue(0.5)); // Create a costmap of 10x10 meters @@ -887,7 +887,7 @@ TEST(GracefulControllerTest, computeVelocityCommandRotate) { } TEST(GracefulControllerTest, computeVelocityCommandRegular) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Create a costmap of 10x10 meters @@ -962,13 +962,13 @@ TEST(GracefulControllerTest, computeVelocityCommandRegular) { } TEST(GracefulControllerTest, computeVelocityCommandRegularBackwards) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Set initial rotation false and allow backward to true - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.initial_rotation", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "test.allow_backward", rclcpp::ParameterValue(true)); // Create a costmap of 10x10 meters @@ -1045,7 +1045,7 @@ TEST(GracefulControllerTest, computeVelocityCommandRegularBackwards) { } TEST(GracefulControllerTest, computeVelocityCommandFinal) { - auto node = std::make_shared("testGraceful"); + auto node = std::make_shared("testGraceful"); auto tf = std::make_shared(node->get_clock()); // Create a costmap of 10x10 meters diff --git a/nav2_lifecycle_manager/CMakeLists.txt b/nav2_lifecycle_manager/CMakeLists.txt index 85179764ee3..48ebccbb84f 100644 --- a/nav2_lifecycle_manager/CMakeLists.txt +++ b/nav2_lifecycle_manager/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(rclcpp REQUIRED) find_package(rclcpp_action REQUIRED) find_package(rclcpp_components REQUIRED) find_package(std_srvs REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -22,10 +23,12 @@ add_library(${library_name} SHARED src/lifecycle_manager.cpp src/lifecycle_manager_client.cpp ) +message(STATUS "nav2_ros_common_INCLUDE_DIRS: ${nav2_ros_common_INCLUDE_DIRS}") target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC bondcpp::bondcpp @@ -48,6 +51,7 @@ target_include_directories(lifecycle_manager PUBLIC "$" "$" + "$" ) target_link_libraries(lifecycle_manager PRIVATE ${library_name} @@ -85,7 +89,7 @@ endif() ament_export_include_directories(include/${PROJECT_NAME}) ament_export_libraries(${library_name}) -ament_export_dependencies(bondcpp diagnostic_updater nav2_util rclcpp rclcpp_action std_srvs) +ament_export_dependencies(bondcpp diagnostic_updater nav2_util rclcpp rclcpp_action std_srvs nav2_ros_common) ament_export_targets(${library_name}) ament_package() diff --git a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp index 8c053bb81eb..b56e08238c8 100644 --- a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp +++ b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager.hpp @@ -24,14 +24,15 @@ #include #include "nav2_util/lifecycle_service_client.hpp" -#include "nav2_util/node_thread.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/node_thread.hpp" +#include "nav2_ros_common/service_server.hpp" #include "rclcpp/rclcpp.hpp" #include "std_srvs/srv/empty.hpp" #include "nav2_msgs/srv/manage_lifecycle_nodes.hpp" #include "std_srvs/srv/trigger.hpp" #include "bondcpp/bond.hpp" #include "diagnostic_updater/diagnostic_updater.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_lifecycle_manager @@ -72,11 +73,11 @@ class LifecycleManager : public rclcpp::Node protected: // Callback group used by services and timers rclcpp::CallbackGroup::SharedPtr callback_group_; - std::unique_ptr service_thread_; + std::unique_ptr service_thread_; // The services provided by this node - nav2_util::ServiceServer::SharedPtr manager_srv_; - nav2_util::ServiceServer::SharedPtr is_active_srv_; + nav2::ServiceServer::SharedPtr manager_srv_; + nav2::ServiceServer::SharedPtr is_active_srv_; /** * @brief Lifecycle node manager callback function * @param request_header Header of the service request diff --git a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp index ddcfe26daca..119aa3c3543 100644 --- a/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp +++ b/nav2_lifecycle_manager/include/nav2_lifecycle_manager/lifecycle_manager_client.hpp @@ -26,7 +26,8 @@ #include "std_srvs/srv/empty.hpp" #include "nav2_msgs/srv/manage_lifecycle_nodes.hpp" #include "std_srvs/srv/trigger.hpp" -#include "nav2_util/service_client.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_client.hpp" namespace nav2_lifecycle_manager { @@ -48,9 +49,25 @@ class LifecycleManagerClient * @param name Managed node name * @param parent_node Node that execute the service calls */ + template explicit LifecycleManagerClient( const std::string & name, - std::shared_ptr parent_node); + NodeT parent_node) + { + manage_service_name_ = name + std::string("/manage_nodes"); + active_service_name_ = name + std::string("/is_active"); + + // Use parent node for service call and logging + logger_ = parent_node->get_logger(); + + // Create the service clients + // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the + // subscription to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode + manager_client_ = nav2::interfaces::create_client( + parent_node, manage_service_name_, true /*creates and spins an internal executor*/); + is_active_client_ = nav2::interfaces::create_client( + parent_node, active_service_name_, true /*creates and spins an internal executor*/); + } // Client-side interface to the Nav2 lifecycle manager /** @@ -107,9 +124,10 @@ class LifecycleManagerClient // The node to use for the service call rclcpp::Node::SharedPtr node_; + rclcpp::Logger logger_{rclcpp::get_logger("nav2_lifecycle_manager_client")}; - nav2_util::ServiceClient::SharedPtr manager_client_; - nav2_util::ServiceClient::SharedPtr is_active_client_; + nav2::ServiceClient::SharedPtr manager_client_; + nav2::ServiceClient::SharedPtr is_active_client_; std::string manage_service_name_; std::string active_service_name_; }; diff --git a/nav2_lifecycle_manager/package.xml b/nav2_lifecycle_manager/package.xml index f70a336d141..99b0b2f9250 100644 --- a/nav2_lifecycle_manager/package.xml +++ b/nav2_lifecycle_manager/package.xml @@ -19,6 +19,7 @@ rclcpp rclcpp_action rclcpp_components + nav2_ros_common std_srvs ament_lint_auto diff --git a/nav2_lifecycle_manager/src/lifecycle_manager.cpp b/nav2_lifecycle_manager/src/lifecycle_manager.cpp index 34f2a793c60..333bda694cc 100644 --- a/nav2_lifecycle_manager/src/lifecycle_manager.cpp +++ b/nav2_lifecycle_manager/src/lifecycle_manager.cpp @@ -99,7 +99,7 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options) } auto executor = std::make_shared(); executor->add_callback_group(callback_group_, get_node_base_interface()); - service_thread_ = std::make_unique(executor); + service_thread_ = std::make_unique(executor); }); diagnostics_updater_.setHardwareID("Nav2"); diagnostics_updater_.add("Nav2 Health", this, &LifecycleManager::CreateDiagnostic); @@ -201,18 +201,19 @@ void LifecycleManager::createLifecycleServiceServers() { message("Creating and initializing lifecycle service servers"); - manager_srv_ = std::make_shared>( - get_name() + std::string("/manage_nodes"), + // Since the LifecycleManager is a special node in that it manages other nodes, + // this is an rclcpp::Node, meaning we can't use the node->create_server API. + // to make a Nav2 ServiceServer. This must be constructed manually using the interfaces. + manager_srv_ = nav2::interfaces::create_service( shared_from_this(), + get_name() + std::string("/manage_nodes"), std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3), - rclcpp::SystemDefaultsQoS(), callback_group_); - is_active_srv_ = std::make_shared>( - get_name() + std::string("/is_active"), + is_active_srv_ = nav2::interfaces::create_service( shared_from_this(), + get_name() + std::string("/is_active"), std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3), - rclcpp::SystemDefaultsQoS(), callback_group_); } diff --git a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp index 7c287f2defb..7b3c4f82c02 100644 --- a/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp +++ b/nav2_lifecycle_manager/src/lifecycle_manager_client.cpp @@ -25,23 +25,6 @@ namespace nav2_lifecycle_manager { using nav2_util::geometry_utils::orientationAroundZAxis; -LifecycleManagerClient::LifecycleManagerClient( - const std::string & name, - std::shared_ptr parent_node) -{ - manage_service_name_ = name + std::string("/manage_nodes"); - active_service_name_ = name + std::string("/is_active"); - - // Use parent node for service call and logging - node_ = parent_node; - - // Create the service clients - manager_client_ = std::make_shared>( - manage_service_name_, node_, true /*creates and spins an internal executor*/); - is_active_client_ = std::make_shared>( - active_service_name_, node_, true /*creates and spins an internal executor*/); -} - bool LifecycleManagerClient::startup(const std::chrono::nanoseconds timeout) { @@ -91,7 +74,7 @@ LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout) auto response = std::make_shared(); RCLCPP_DEBUG( - node_->get_logger(), "Waiting for the %s service...", + logger_, "Waiting for the %s service...", active_service_name_.c_str()); if (!is_active_client_->wait_for_service(std::chrono::seconds(1))) { @@ -99,7 +82,7 @@ LifecycleManagerClient::is_active(const std::chrono::nanoseconds timeout) } RCLCPP_DEBUG( - node_->get_logger(), "Sending %s request", + logger_, "Sending %s request", active_service_name_.c_str()); try { @@ -122,19 +105,19 @@ LifecycleManagerClient::callService(uint8_t command, const std::chrono::nanoseco request->command = command; RCLCPP_DEBUG( - node_->get_logger(), "Waiting for the %s service...", + logger_, "Waiting for the %s service...", manage_service_name_.c_str()); while (!manager_client_->wait_for_service(timeout)) { if (!rclcpp::ok()) { - RCLCPP_ERROR(node_->get_logger(), "Client interrupted while waiting for service to appear"); + RCLCPP_ERROR(logger_, "Client interrupted while waiting for service to appear"); return false; } - RCLCPP_DEBUG(node_->get_logger(), "Waiting for service to appear..."); + RCLCPP_DEBUG(logger_, "Waiting for service to appear..."); } RCLCPP_DEBUG( - node_->get_logger(), "Sending %s request", + logger_, "Sending %s request", manage_service_name_.c_str()); try { auto future_result = manager_client_->invoke(request, timeout); diff --git a/nav2_lifecycle_manager/test/test_bond.cpp b/nav2_lifecycle_manager/test/test_bond.cpp index 38c772e6b1b..b2dbc10115f 100644 --- a/nav2_lifecycle_manager/test/test_bond.cpp +++ b/nav2_lifecycle_manager/test/test_bond.cpp @@ -17,19 +17,19 @@ #include #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_lifecycle_manager/lifecycle_manager.hpp" #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp" using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; // minimal lifecycle node implementing bond as in rest of navigation servers -class TestLifecycleNode : public nav2_util::LifecycleNode +class TestLifecycleNode : public nav2::LifecycleNode { public: TestLifecycleNode(bool bond, std::string name) - : nav2_util::LifecycleNode(name) + : nav2::LifecycleNode(name, rclcpp::NodeOptions()) { state = ""; enable_bond = bond; @@ -118,11 +118,11 @@ class TestFixture TestFixture(bool bond, std::string node_name) { lf_node_ = std::make_shared(bond, node_name); - lf_thread_ = std::make_unique(lf_node_->get_node_base_interface()); + lf_thread_ = std::make_unique(lf_node_->get_node_base_interface()); } std::shared_ptr lf_node_; - std::unique_ptr lf_thread_; + std::unique_ptr lf_thread_; }; TEST(LifecycleBondTest, POSITIVE) diff --git a/nav2_lifecycle_manager/test/test_lifecycle_manager.cpp b/nav2_lifecycle_manager/test/test_lifecycle_manager.cpp index c2c0cb75f0b..0f3997370f0 100644 --- a/nav2_lifecycle_manager/test/test_lifecycle_manager.cpp +++ b/nav2_lifecycle_manager/test/test_lifecycle_manager.cpp @@ -16,17 +16,17 @@ #include #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_lifecycle_manager/lifecycle_manager_client.hpp" using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; -class LifecycleNodeTest : public rclcpp_lifecycle::LifecycleNode +class LifecycleNodeTest : public nav2::LifecycleNode { public: LifecycleNodeTest() - : rclcpp_lifecycle::LifecycleNode("lifecycle_node_test") {} + : nav2::LifecycleNode("lifecycle_node_test") {} CallbackReturn on_configure(const rclcpp_lifecycle::State & /*state*/) override { @@ -71,12 +71,12 @@ class LifecycleClientTestFixture LifecycleClientTestFixture() { lf_node_ = std::make_shared(); - lf_thread_ = std::make_unique(lf_node_->get_node_base_interface()); + lf_thread_ = std::make_unique(lf_node_->get_node_base_interface()); } private: std::shared_ptr lf_node_; - std::unique_ptr lf_thread_; + std::unique_ptr lf_thread_; }; TEST(LifecycleClientTest, BasicTest) diff --git a/nav2_map_server/CMakeLists.txt b/nav2_map_server/CMakeLists.txt index c193685363b..d742a54a475 100644 --- a/nav2_map_server/CMakeLists.txt +++ b/nav2_map_server/CMakeLists.txt @@ -15,6 +15,7 @@ find_package(rclcpp_components REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2 REQUIRED) +find_package(nav2_ros_common REQUIRED) find_package(yaml_cpp_vendor REQUIRED) find_package(yaml-cpp REQUIRED) @@ -38,10 +39,12 @@ add_library(${map_io_library_name} SHARED target_include_directories(${map_io_library_name} PUBLIC "$" - "$") + "$" + "$") target_include_directories(${map_io_library_name} PRIVATE - ${GRAPHICSMAGICKCPP_INCLUDE_DIRS}) + ${GRAPHICSMAGICKCPP_INCLUDE_DIRS} + "$") target_link_libraries(${map_io_library_name} PUBLIC nav2_util::nav2_util_core ${nav_msgs_TARGETS} @@ -59,7 +62,8 @@ add_library(${library_name} SHARED target_include_directories(${library_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${library_name} PUBLIC ${map_io_library_name} ${nav_msgs_TARGETS} @@ -79,7 +83,8 @@ add_executable(${map_server_executable} target_include_directories(${map_server_executable} PRIVATE "$" - "$") + "$" + "$") target_link_libraries(${map_server_executable} PRIVATE ${library_name} ${map_io_library_name} @@ -91,7 +96,8 @@ add_executable(${map_saver_cli_executable} target_include_directories(${map_saver_cli_executable} PRIVATE "$" - "$") + "$" + "$") target_link_libraries(${map_saver_cli_executable} PRIVATE ${library_name} ${map_io_library_name} @@ -107,7 +113,8 @@ add_executable(${map_saver_server_executable} target_include_directories(${map_saver_server_executable} PRIVATE "$" - "$") + "$" + "$") target_link_libraries(${map_saver_server_executable} PRIVATE ${library_name} ${map_io_library_name} @@ -123,7 +130,8 @@ add_executable(${costmap_filter_info_server_executable} target_include_directories(${costmap_filter_info_server_executable} PRIVATE "$" - "$") + "$" + "$") target_link_libraries(${costmap_filter_info_server_executable} PRIVATE ${library_name} ${map_io_library_name} @@ -171,7 +179,7 @@ ament_export_libraries( ${library_name} ${map_io_library_name} ) -ament_export_dependencies(nav_msgs nav2_msgs nav2_util rclcpp rclcpp_lifecycle) +ament_export_dependencies(nav_msgs nav2_msgs nav2_util rclcpp rclcpp_lifecycle nav2_ros_common) ament_export_targets(${library_name}) ament_package() diff --git a/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp b/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp index aa024f6dc04..9a156dcd586 100644 --- a/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp +++ b/nav2_map_server/include/nav2_map_server/costmap_filter_info_server.hpp @@ -19,13 +19,13 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/state.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/msg/costmap_filter_info.hpp" namespace nav2_map_server { -class CostmapFilterInfoServer : public nav2_util::LifecycleNode +class CostmapFilterInfoServer : public nav2::LifecycleNode { public: /** @@ -45,34 +45,34 @@ class CostmapFilterInfoServer : public nav2_util::LifecycleNode * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Publishes a CostmapFilterInfo message * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivates publisher * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Resets publisher * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in Shutdown state * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; private: - rclcpp_lifecycle::LifecyclePublisher::SharedPtr publisher_; + nav2::Publisher::SharedPtr publisher_; nav2_msgs::msg::CostmapFilterInfo msg_; }; // CostmapFilterInfoServer diff --git a/nav2_map_server/include/nav2_map_server/map_saver.hpp b/nav2_map_server/include/nav2_map_server/map_saver.hpp index 123e6723b80..487c72aaa6a 100644 --- a/nav2_map_server/include/nav2_map_server/map_saver.hpp +++ b/nav2_map_server/include/nav2_map_server/map_saver.hpp @@ -21,9 +21,9 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/state.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/srv/save_map.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/service_server.hpp" #include "map_io.hpp" @@ -34,7 +34,7 @@ namespace nav2_map_server * @class nav2_map_server::MapSaver * @brief A class that provides map saving methods and services */ -class MapSaver : public nav2_util::LifecycleNode +class MapSaver : public nav2::LifecycleNode { public: /** @@ -63,31 +63,31 @@ class MapSaver : public nav2_util::LifecycleNode * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Called when node switched to active state * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Called when node switched to inactive state * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Called when it is required node clean-up * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in Shutdown state * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; protected: /** @@ -112,8 +112,7 @@ class MapSaver : public nav2_util::LifecycleNode // The name of the service for saving a map from topic const std::string save_map_service_name_{"save_map"}; // A service to save the map to a file at run time (SaveMap) - nav2_util::ServiceServer>::SharedPtr save_map_service_; + nav2::ServiceServer::SharedPtr save_map_service_; }; } // namespace nav2_map_server diff --git a/nav2_map_server/include/nav2_map_server/map_server.hpp b/nav2_map_server/include/nav2_map_server/map_server.hpp index 4e6ca327b57..ed7a6ab9d89 100644 --- a/nav2_map_server/include/nav2_map_server/map_server.hpp +++ b/nav2_map_server/include/nav2_map_server/map_server.hpp @@ -18,8 +18,8 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_server.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" #include "nav_msgs/srv/get_map.hpp" #include "nav2_msgs/srv/load_map.hpp" @@ -34,7 +34,7 @@ namespace nav2_map_server * @brief Parses the map yaml file and creates a service and a publisher that * provides occupancy grid */ -class MapServer : public nav2_util::LifecycleNode +class MapServer : public nav2::LifecycleNode { public: /** @@ -54,31 +54,31 @@ class MapServer : public nav2_util::LifecycleNode * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Start publishing the map using the latched topic * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Stops publishing the latched topic * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Resets the member variables * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in Shutdown state * @param state Lifecycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** * @brief Load the map YAML, image from map file name and @@ -126,15 +126,13 @@ class MapServer : public nav2_util::LifecycleNode const std::string load_map_service_name_{"load_map"}; // A service to provide the occupancy grid (GetMap) and the message to return - nav2_util::ServiceServer>::SharedPtr occ_service_; + nav2::ServiceServer::SharedPtr occ_service_; // A service to load the occupancy grid from file at run time (LoadMap) - nav2_util::ServiceServer>::SharedPtr load_map_service_; + nav2::ServiceServer::SharedPtr load_map_service_; // A topic on which the occupancy grid will be published - rclcpp_lifecycle::LifecyclePublisher::SharedPtr occ_pub_; + nav2::Publisher::SharedPtr occ_pub_; // The frame ID used in the returned OccupancyGrid message std::string frame_id_; diff --git a/nav2_map_server/package.xml b/nav2_map_server/package.xml index 9b4d47790b7..f6d5f75a278 100644 --- a/nav2_map_server/package.xml +++ b/nav2_map_server/package.xml @@ -26,6 +26,7 @@ nav2_util graphicsmagick lifecycle_msgs + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp b/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp index ae917b211fd..a1be5a3abb3 100644 --- a/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp +++ b/nav2_map_server/src/costmap_filter_info/costmap_filter_info_server.cpp @@ -25,7 +25,7 @@ namespace nav2_map_server { CostmapFilterInfoServer::CostmapFilterInfoServer(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("costmap_filter_info_server", "", options) +: nav2::LifecycleNode("costmap_filter_info_server", "", options) { declare_parameter("filter_info_topic", "costmap_filter_info"); declare_parameter("type", 0); @@ -38,7 +38,7 @@ CostmapFilterInfoServer::~CostmapFilterInfoServer() { } -nav2_util::CallbackReturn +nav2::CallbackReturn CostmapFilterInfoServer::on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -46,7 +46,7 @@ CostmapFilterInfoServer::on_configure(const rclcpp_lifecycle::State & /*state*/) std::string filter_info_topic = get_parameter("filter_info_topic").as_string(); publisher_ = this->create_publisher( - filter_info_topic, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + filter_info_topic, nav2::qos::LatchedPublisherQoS()); msg_ = nav2_msgs::msg::CostmapFilterInfo(); msg_.header.frame_id = ""; @@ -56,10 +56,10 @@ CostmapFilterInfoServer::on_configure(const rclcpp_lifecycle::State & /*state*/) msg_.base = static_cast(get_parameter("base").as_double()); msg_.multiplier = static_cast(get_parameter("multiplier").as_double()); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CostmapFilterInfoServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -71,10 +71,10 @@ CostmapFilterInfoServer::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CostmapFilterInfoServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -84,25 +84,25 @@ CostmapFilterInfoServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/ // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CostmapFilterInfoServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); publisher_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn CostmapFilterInfoServer::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } } // namespace nav2_map_server diff --git a/nav2_map_server/src/map_saver/map_saver.cpp b/nav2_map_server/src/map_saver/map_saver.cpp index 43226a00349..1a54ac77a1c 100644 --- a/nav2_map_server/src/map_saver/map_saver.cpp +++ b/nav2_map_server/src/map_saver/map_saver.cpp @@ -42,7 +42,7 @@ using namespace std::placeholders; namespace nav2_map_server { MapSaver::MapSaver(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("map_saver", "", options) +: nav2::LifecycleNode("map_saver", "", options) { RCLCPP_INFO(get_logger(), "Creating"); @@ -57,7 +57,7 @@ MapSaver::~MapSaver() { } -nav2_util::CallbackReturn +nav2::CallbackReturn MapSaver::on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -72,16 +72,14 @@ MapSaver::on_configure(const rclcpp_lifecycle::State & /*state*/) map_subscribe_transient_local_ = get_parameter("map_subscribe_transient_local").as_bool(); // Create a service that saves the occupancy grid from map topic to a file - save_map_service_ = std::make_shared>>( + save_map_service_ = create_service( service_prefix + save_map_service_name_, - shared_from_this(), std::bind(&MapSaver::saveMapCallback, this, _1, _2, _3)); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapSaver::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -89,10 +87,10 @@ MapSaver::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapSaver::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -100,24 +98,24 @@ MapSaver::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapSaver::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); save_map_service_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapSaver::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } void MapSaver::saveMapCallback( @@ -188,11 +186,9 @@ bool MapSaver::saveMapTopicToFile( prom.set_value(msg); }; - rclcpp::QoS map_qos(10); // initialize to default + rclcpp::QoS map_qos = nav2::qos::StandardTopicQoS(); // initialize to default if (map_subscribe_transient_local_) { - map_qos.transient_local(); - map_qos.reliable(); - map_qos.keep_last(1); + map_qos = nav2::qos::LatchedSubscriptionQoS(); } // Create new CallbackGroup for map_sub @@ -200,10 +196,8 @@ bool MapSaver::saveMapTopicToFile( rclcpp::CallbackGroupType::MutuallyExclusive, false); - auto option = rclcpp::SubscriptionOptions(); - option.callback_group = callback_group; auto map_sub = create_subscription( - map_topic_loc, map_qos, mapCallback, option); + map_topic_loc, mapCallback, map_qos, callback_group); // Create SingleThreadedExecutor to spin map_sub in callback_group rclcpp::executors::SingleThreadedExecutor executor; diff --git a/nav2_map_server/src/map_server/map_server.cpp b/nav2_map_server/src/map_server/map_server.cpp index a9470ef9ce6..0be2f656668 100644 --- a/nav2_map_server/src/map_server/map_server.cpp +++ b/nav2_map_server/src/map_server/map_server.cpp @@ -63,7 +63,7 @@ namespace nav2_map_server { MapServer::MapServer(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("map_server", "", options), map_available_(false) +: nav2::LifecycleNode("map_server", "", options), map_available_(false) { RCLCPP_INFO(get_logger(), "Creating"); @@ -77,7 +77,7 @@ MapServer::~MapServer() { } -nav2_util::CallbackReturn +nav2::CallbackReturn MapServer::on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -108,28 +108,24 @@ MapServer::on_configure(const rclcpp_lifecycle::State & /*state*/) const std::string service_prefix = get_name() + std::string("/"); // Create a service that provides the occupancy grid - occ_service_ = std::make_shared>>( + occ_service_ = create_service( service_prefix + std::string(service_name_), - shared_from_this(), std::bind(&MapServer::getMapCallback, this, _1, _2, _3)); // Create a publisher using the QoS settings to emulate a ROS1 latched topic occ_pub_ = create_publisher( topic_name, - rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + nav2::qos::LatchedPublisherQoS()); // Create a service that loads the occupancy grid from a file - load_map_service_ = std::make_shared>>( + load_map_service_ = create_service( service_prefix + std::string(load_map_service_name_), - shared_from_this(), std::bind(&MapServer::loadMapCallback, this, _1, _2, _3)); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -144,10 +140,10 @@ MapServer::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -157,10 +153,10 @@ MapServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -171,14 +167,14 @@ MapServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) map_available_ = false; msg_ = nav_msgs::msg::OccupancyGrid(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn MapServer::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } void MapServer::getMapCallback( diff --git a/nav2_map_server/test/unit/test_costmap_filter_info_server.cpp b/nav2_map_server/test/unit/test_costmap_filter_info_server.cpp index 024e1d41497..4fcd8aec35e 100644 --- a/nav2_map_server/test/unit/test_costmap_filter_info_server.cpp +++ b/nav2_map_server/test/unit/test_costmap_filter_info_server.cpp @@ -88,8 +88,9 @@ class InfoServerTester : public ::testing::Test info_server_->start(); subscription_ = info_server_->create_subscription( - FILTER_INFO_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), - std::bind(&InfoServerTester::infoCallback, this, std::placeholders::_1)); + FILTER_INFO_TOPIC, + std::bind(&InfoServerTester::infoCallback, this, std::placeholders::_1), + nav2::qos::LatchedSubscriptionQoS()); } ~InfoServerTester() @@ -125,7 +126,7 @@ class InfoServerTester : public ::testing::Test info_ = msg; } - rclcpp::Subscription::SharedPtr subscription_; + nav2::Subscription::SharedPtr subscription_; mutex_t * access_; }; diff --git a/nav2_map_server/test/unit/test_map_io.cpp b/nav2_map_server/test/unit/test_map_io.cpp index 7b57bb3d883..9efbed9a585 100644 --- a/nav2_map_server/test/unit/test_map_io.cpp +++ b/nav2_map_server/test/unit/test_map_io.cpp @@ -43,7 +43,7 @@ #include "yaml-cpp/yaml.h" #include "nav2_map_server/map_io.hpp" #include "nav2_map_server/map_server.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "test_constants/test_constants.h" #define TEST_DIR TEST_DIRECTORY diff --git a/nav2_mppi_controller/CMakeLists.txt b/nav2_mppi_controller/CMakeLists.txt index 3f2b40688cd..d38678171eb 100644 --- a/nav2_mppi_controller/CMakeLists.txt +++ b/nav2_mppi_controller/CMakeLists.txt @@ -17,6 +17,7 @@ find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(tf2_ros REQUIRED) find_package(visualization_msgs REQUIRED) +find_package(nav2_ros_common REQUIRED) find_package(Eigen3 REQUIRED) include_directories( @@ -49,7 +50,8 @@ target_compile_options(mppi_controller PUBLIC -O3) target_include_directories(mppi_controller PUBLIC "$" - "$") + "$" + "$") target_link_libraries(mppi_controller PUBLIC angles::angles ${geometry_msgs_TARGETS} @@ -84,7 +86,8 @@ target_compile_options(mppi_critics PUBLIC -fconcepts -O3) target_include_directories(mppi_critics PUBLIC "$" - "$") + "$" + "$") target_link_libraries(mppi_critics PUBLIC angles::angles ${geometry_msgs_TARGETS} @@ -142,6 +145,7 @@ ament_export_dependencies( tf2_geometry_msgs tf2_ros visualization_msgs + nav2_ros_common Eigen3 ) ament_export_include_directories(include/${PROJECT_NAME}) diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/controller.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/controller.hpp index c2fc9b5cc9e..1c52df96f68 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/controller.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/controller.hpp @@ -23,10 +23,9 @@ #include "nav2_mppi_controller/tools/trajectory_visualizer.hpp" #include "nav2_mppi_controller/models/constraints.hpp" #include "nav2_mppi_controller/tools/utils.hpp" - +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/controller.hpp" #include "nav2_core/goal_checker.hpp" -#include "rclcpp/rclcpp.hpp" namespace nav2_mppi_controller { @@ -53,7 +52,7 @@ class MPPIController : public nav2_core::Controller * @param costmap_ros Costmap2DROS object of environment */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, const std::shared_ptr tf, const std::shared_ptr costmap_ros) override; @@ -114,11 +113,11 @@ class MPPIController : public nav2_core::Controller const Eigen::ArrayXXf & optimal_trajectory); std::string name_; - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_; + nav2::LifecycleNode::WeakPtr parent_; rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")}; std::shared_ptr costmap_ros_; std::shared_ptr tf_buffer_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr opt_traj_pub_; + nav2::Publisher::SharedPtr opt_traj_pub_; std::unique_ptr parameters_handler_; Optimizer optimizer_; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/critic_function.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/critic_function.hpp index 88d277c14ee..9b7d17aaea5 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/critic_function.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/critic_function.hpp @@ -63,7 +63,7 @@ class CriticFunction * @param dynamic_parameter_handler Parameter handler object */ void on_configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, + nav2::LifecycleNode::WeakPtr parent, const std::string & parent_name, const std::string & name, std::shared_ptr costmap_ros, @@ -105,7 +105,7 @@ class CriticFunction protected: bool enabled_; std::string name_, parent_name_; - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_; + nav2::LifecycleNode::WeakPtr parent_; std::shared_ptr costmap_ros_; nav2_costmap_2d::Costmap2D * costmap_{nullptr}; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp index 8790476b5df..fed85867905 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/critic_manager.hpp @@ -61,7 +61,7 @@ class CriticManager * @param dynamic_parameter_handler Parameter handler object */ void on_configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, std::shared_ptr, ParametersHandler *); /** @@ -87,7 +87,7 @@ class CriticManager std::string getFullName(const std::string & name); protected: - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_; + nav2::LifecycleNode::WeakPtr parent_; std::shared_ptr costmap_ros_; std::string name_; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp index 2ced1fe2fc4..34cd9a95276 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/optimizer.hpp @@ -70,7 +70,7 @@ class Optimizer * @param dynamic_parameter_handler Parameter handler object */ void initialize( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, std::shared_ptr costmap_ros, ParametersHandler * dynamic_parameters_handler); @@ -250,7 +250,7 @@ class Optimizer bool fallback(bool fail); protected: - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_; + nav2::LifecycleNode::WeakPtr parent_; std::shared_ptr costmap_ros_; nav2_costmap_2d::Costmap2D * costmap_; std::string name_; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/noise_generator.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/noise_generator.hpp index 5823d648782..a201a1d4d1b 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/noise_generator.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/noise_generator.hpp @@ -24,6 +24,7 @@ #include #include +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_mppi_controller/models/optimizer_settings.hpp" #include "nav2_mppi_controller/tools/parameters_handler.hpp" #include "nav2_mppi_controller/models/control_sequence.hpp" diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp index 28f0eaf3997..8aa8c1744a9 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/parameters_handler.hpp @@ -22,7 +22,8 @@ #include #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp/parameter_value.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" @@ -55,7 +56,7 @@ class ParametersHandler * @param parent Weak ptr to node */ explicit ParametersHandler( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string & name); + const nav2::LifecycleNode::WeakPtr & parent, std::string & name); /** * @brief Destructor for mppi::ParametersHandler @@ -150,8 +151,11 @@ class ParametersHandler * @param name Parameter name * @param node Node to set parameter via */ - template - void setParam(SettingT & setting, const std::string & name, NodeT node) const; + template + void setParam( + SettingT & setting, + const std::string & name, + nav2::LifecycleNode::SharedPtr node) const; /** * @brief Converts parameter type to real types @@ -165,7 +169,7 @@ class ParametersHandler rclcpp::Logger logger_{rclcpp::get_logger("MPPIController")}; rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_param_handler_; - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; std::string node_name_; std::string name_; @@ -215,16 +219,16 @@ void ParametersHandler::getParam( { auto node = node_.lock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name, rclcpp::ParameterValue(default_value)); setParam(setting, name, node); setParamCallback(setting, name, param_type); } -template +template void ParametersHandler::setParam( - SettingT & setting, const std::string & name, NodeT node) const + SettingT & setting, const std::string & name, nav2::LifecycleNode::SharedPtr node) const { ParamT param_in{}; node->get_parameter(name, param_in); diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp index 439d21eaf29..cfa87f5ace4 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/path_handler.hpp @@ -22,7 +22,7 @@ #include #include -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/buffer.h" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/path.hpp" @@ -66,7 +66,7 @@ class PathHandler * @param dynamic_parameter_handler Parameter handler object */ void initialize( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, std::shared_ptr, std::shared_ptr, ParametersHandler *); diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp index c60d8637c97..f57d9b6b2b2 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/trajectory_visualizer.hpp @@ -21,8 +21,7 @@ #include #include "nav_msgs/msg/path.hpp" -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "nav2_mppi_controller/tools/parameters_handler.hpp" @@ -52,7 +51,7 @@ class TrajectoryVisualizer * @param dynamic_parameter_handler Parameter handler object */ void on_configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, const std::string & frame_id, ParametersHandler * parameters_handler); /** @@ -97,10 +96,10 @@ class TrajectoryVisualizer protected: std::string frame_id_; - std::shared_ptr> - trajectories_publisher_; - std::shared_ptr> transformed_path_pub_; - std::shared_ptr> optimal_path_pub_; + nav2::Publisher::SharedPtr + trajectories_publisher_; + nav2::Publisher::SharedPtr transformed_path_pub_; + nav2::Publisher::SharedPtr optimal_path_pub_; std::unique_ptr optimal_path_; std::unique_ptr points_; diff --git a/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp b/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp index 804f317892c..f518f16e169 100644 --- a/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp +++ b/nav2_mppi_controller/include/nav2_mppi_controller/tools/utils.hpp @@ -38,7 +38,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_core/goal_checker.hpp" #include "nav2_mppi_controller/models/optimizer_settings.hpp" diff --git a/nav2_mppi_controller/package.xml b/nav2_mppi_controller/package.xml index 08e7ef8a23e..0a5b0158f8c 100644 --- a/nav2_mppi_controller/package.xml +++ b/nav2_mppi_controller/package.xml @@ -29,6 +29,7 @@ visualization_msgs eigen3_cmake_module eigen + nav2_ros_common ament_lint_auto ament_lint_common diff --git a/nav2_mppi_controller/src/controller.cpp b/nav2_mppi_controller/src/controller.cpp index 9c6c7c209a5..29059ae98cc 100644 --- a/nav2_mppi_controller/src/controller.cpp +++ b/nav2_mppi_controller/src/controller.cpp @@ -23,7 +23,7 @@ namespace nav2_mppi_controller { void MPPIController::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, const std::shared_ptr tf, const std::shared_ptr costmap_ros) { @@ -49,7 +49,7 @@ void MPPIController::configure( if (publish_optimal_trajectory_) { opt_traj_pub_ = node->create_publisher( - "~/optimal_trajectory", rclcpp::SystemDefaultsQoS()); + "~/optimal_trajectory"); } RCLCPP_INFO(logger_, "Configured MPPI Controller: %s", name_.c_str()); diff --git a/nav2_mppi_controller/src/critic_manager.cpp b/nav2_mppi_controller/src/critic_manager.cpp index 2065c5b241b..d6acd320b05 100644 --- a/nav2_mppi_controller/src/critic_manager.cpp +++ b/nav2_mppi_controller/src/critic_manager.cpp @@ -18,7 +18,7 @@ namespace mppi { void CriticManager::on_configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, std::shared_ptr costmap_ros, ParametersHandler * param_handler) { parent_ = parent; diff --git a/nav2_mppi_controller/src/optimizer.cpp b/nav2_mppi_controller/src/optimizer.cpp index 6e63361ede1..7f34a74e240 100644 --- a/nav2_mppi_controller/src/optimizer.cpp +++ b/nav2_mppi_controller/src/optimizer.cpp @@ -30,7 +30,7 @@ namespace mppi { void Optimizer::initialize( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, std::shared_ptr costmap_ros, ParametersHandler * param_handler) { diff --git a/nav2_mppi_controller/src/parameters_handler.cpp b/nav2_mppi_controller/src/parameters_handler.cpp index 4d540ef1cae..3d96422acdc 100644 --- a/nav2_mppi_controller/src/parameters_handler.cpp +++ b/nav2_mppi_controller/src/parameters_handler.cpp @@ -18,7 +18,7 @@ namespace mppi { ParametersHandler::ParametersHandler( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string & name) + const nav2::LifecycleNode::WeakPtr & parent, std::string & name) { node_ = parent; auto node = node_.lock(); diff --git a/nav2_mppi_controller/src/path_handler.cpp b/nav2_mppi_controller/src/path_handler.cpp index d9138a2bfc2..93593982c5c 100644 --- a/nav2_mppi_controller/src/path_handler.cpp +++ b/nav2_mppi_controller/src/path_handler.cpp @@ -22,7 +22,7 @@ namespace mppi { void PathHandler::initialize( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, std::shared_ptr costmap, std::shared_ptr buffer, ParametersHandler * param_handler) { diff --git a/nav2_mppi_controller/src/trajectory_visualizer.cpp b/nav2_mppi_controller/src/trajectory_visualizer.cpp index de4f2249fb9..6960b5676c6 100644 --- a/nav2_mppi_controller/src/trajectory_visualizer.cpp +++ b/nav2_mppi_controller/src/trajectory_visualizer.cpp @@ -19,17 +19,17 @@ namespace mppi { void TrajectoryVisualizer::on_configure( - rclcpp_lifecycle::LifecycleNode::WeakPtr parent, const std::string & name, + nav2::LifecycleNode::WeakPtr parent, const std::string & name, const std::string & frame_id, ParametersHandler * parameters_handler) { auto node = parent.lock(); logger_ = node->get_logger(); frame_id_ = frame_id; trajectories_publisher_ = - node->create_publisher("~/candidate_trajectories", 1); + node->create_publisher("~/candidate_trajectories"); transformed_path_pub_ = node->create_publisher( - "~/transformed_global_plan", 1); - optimal_path_pub_ = node->create_publisher("~/optimal_path", 1); + "~/transformed_global_plan"); + optimal_path_pub_ = node->create_publisher("~/optimal_path"); parameters_handler_ = parameters_handler; auto getParam = parameters_handler->getParamGetter(name + ".TrajectoryVisualizer"); diff --git a/nav2_mppi_controller/test/critic_manager_test.cpp b/nav2_mppi_controller/test/critic_manager_test.cpp index a9017569ae1..ff0116ed7de 100644 --- a/nav2_mppi_controller/test/critic_manager_test.cpp +++ b/nav2_mppi_controller/test/critic_manager_test.cpp @@ -92,7 +92,7 @@ class CriticManagerWrapperEnum : public CriticManager TEST(CriticManagerTests, BasicCriticOperations) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -129,7 +129,7 @@ TEST(CriticManagerTests, BasicCriticOperations) TEST(CriticManagerTests, CriticLoadingTest) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); node->declare_parameter( "critic_manager.critics", rclcpp::ParameterValue(std::vector{"ConstraintCritic", "PreferForwardCritic"})); diff --git a/nav2_mppi_controller/test/critics_tests.cpp b/nav2_mppi_controller/test/critics_tests.cpp index 9a7b5b8225d..813cba14318 100644 --- a/nav2_mppi_controller/test/critics_tests.cpp +++ b/nav2_mppi_controller/test/critics_tests.cpp @@ -59,7 +59,7 @@ class PathAngleCriticWrapper : public PathAngleCritic TEST(CriticTests, ConstraintsCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -128,7 +128,7 @@ TEST(CriticTests, ConstraintsCritic) } TEST(CriticTests, ObstacleCriticMisalignedParams) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -149,7 +149,7 @@ TEST(CriticTests, ObstacleCriticMisalignedParams) { } TEST(CriticTests, ObstacleCriticAlignedParams) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -169,7 +169,7 @@ TEST(CriticTests, ObstacleCriticAlignedParams) { TEST(CriticTests, CostCriticMisAlignedParams) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -190,7 +190,7 @@ TEST(CriticTests, CostCriticMisAlignedParams) { TEST(CriticTests, CostCriticAlignedParams) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -209,7 +209,7 @@ TEST(CriticTests, CostCriticAlignedParams) { TEST(CriticTests, GoalAngleCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -269,7 +269,7 @@ TEST(CriticTests, GoalAngleCritic) TEST(CriticTests, GoalCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -322,7 +322,7 @@ TEST(CriticTests, GoalCritic) TEST(CriticTests, PathAngleCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -441,7 +441,7 @@ TEST(CriticTests, PathAngleCritic) TEST(CriticTests, PreferForwardCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -498,7 +498,7 @@ TEST(CriticTests, PreferForwardCritic) TEST(CriticTests, TwirlingCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -563,7 +563,7 @@ TEST(CriticTests, TwirlingCritic) TEST(CriticTests, PathFollowCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -615,7 +615,7 @@ TEST(CriticTests, PathFollowCritic) TEST(CriticTests, PathAlignCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; @@ -726,7 +726,7 @@ TEST(CriticTests, PathAlignCritic) TEST(CriticTests, VelocityDeadbandCritic) { // Standard preamble - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); std::string name = "test"; diff --git a/nav2_mppi_controller/test/motion_model_tests.cpp b/nav2_mppi_controller/test/motion_model_tests.cpp index c473e97dbc9..a40be555fce 100644 --- a/nav2_mppi_controller/test/motion_model_tests.cpp +++ b/nav2_mppi_controller/test/motion_model_tests.cpp @@ -126,7 +126,7 @@ TEST(MotionModelTests, AckermannTest) int timesteps = 50; control_sequence.reset(timesteps); // populates with zeros state.reset(batches, timesteps); // populates with zeros - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; ParametersHandler param_handler(node, name); std::unique_ptr model = @@ -185,7 +185,7 @@ TEST(MotionModelTests, AckermannReversingTest) control_sequence.reset(timesteps); // populates with zeros control_sequence2.reset(timesteps); // populates with zeros state.reset(batches, timesteps); // populates with zeros - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; ParametersHandler param_handler(node, name); std::unique_ptr model = diff --git a/nav2_mppi_controller/test/noise_generator_test.cpp b/nav2_mppi_controller/test/noise_generator_test.cpp index 6e86f60363b..a051782d311 100644 --- a/nav2_mppi_controller/test/noise_generator_test.cpp +++ b/nav2_mppi_controller/test/noise_generator_test.cpp @@ -36,7 +36,7 @@ TEST(NoiseGeneratorTest, NoiseGeneratorLifecycle) settings.batch_size = 100; settings.time_steps = 25; - auto node = std::make_shared("node"); + auto node = std::make_shared("node"); node->declare_parameter("test_name.regenerate_noises", rclcpp::ParameterValue(false)); std::string name = "test"; ParametersHandler handler(node, name); @@ -49,7 +49,7 @@ ParametersHandler handler(node, name); TEST(NoiseGeneratorTest, NoiseGeneratorMain) { // Tests shuts down internal thread cleanly - auto node = std::make_shared("node"); + auto node = std::make_shared("node"); node->declare_parameter("test_name.regenerate_noises", rclcpp::ParameterValue(true)); std::string name = "test"; ParametersHandler handler(node, name); @@ -138,7 +138,7 @@ ParametersHandler handler(node, name); TEST(NoiseGeneratorTest, NoiseGeneratorMainNoRegenerate) { // This time with no regeneration of noises - auto node = std::make_shared("node"); + auto node = std::make_shared("node"); node->declare_parameter("test_name.regenerate_noises", rclcpp::ParameterValue(false)); std::string name = "test"; ParametersHandler handler(node, name); diff --git a/nav2_mppi_controller/test/optimizer_unit_tests.cpp b/nav2_mppi_controller/test/optimizer_unit_tests.cpp index 1c3732399e6..5c856489c6d 100644 --- a/nav2_mppi_controller/test/optimizer_unit_tests.cpp +++ b/nav2_mppi_controller/test/optimizer_unit_tests.cpp @@ -220,7 +220,7 @@ class OptimizerTester : public Optimizer TEST(OptimizerTests, BasicInitializedFunctions) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); node->declare_parameter("mppic.time_steps", rclcpp::ParameterValue(50)); @@ -262,7 +262,7 @@ TEST(OptimizerTests, BasicInitializedFunctions) TEST(OptimizerTests, TestOptimizerMotionModels) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); auto costmap_ros = std::make_shared( @@ -292,7 +292,7 @@ TEST(OptimizerTests, TestOptimizerMotionModels) TEST(OptimizerTests, setOffsetTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("mppic.model_dt", rclcpp::ParameterValue(0.1)); node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); @@ -317,7 +317,7 @@ TEST(OptimizerTests, setOffsetTests) TEST(OptimizerTests, resetTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -337,7 +337,7 @@ TEST(OptimizerTests, resetTests) TEST(OptimizerTests, FallbackTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -362,7 +362,7 @@ TEST(OptimizerTests, FallbackTests) TEST(OptimizerTests, PrepareTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -391,7 +391,7 @@ TEST(OptimizerTests, PrepareTests) TEST(OptimizerTests, shiftControlSequenceTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -435,7 +435,7 @@ TEST(OptimizerTests, shiftControlSequenceTests) TEST(OptimizerTests, SpeedLimitTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -473,7 +473,7 @@ TEST(OptimizerTests, SpeedLimitTests) TEST(OptimizerTests, applyControlSequenceConstraintsTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -530,7 +530,7 @@ TEST(OptimizerTests, applyControlSequenceConstraintsTests) TEST(OptimizerTests, updateStateVelocitiesTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -561,7 +561,7 @@ TEST(OptimizerTests, updateStateVelocitiesTests) TEST(OptimizerTests, getControlFromSequenceAsTwistTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -600,7 +600,7 @@ TEST(OptimizerTests, getControlFromSequenceAsTwistTests) TEST(OptimizerTests, integrateStateVelocitiesTests) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); OptimizerTester optimizer_tester; node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); node->declare_parameter("mppic.batch_size", rclcpp::ParameterValue(1000)); @@ -671,7 +671,7 @@ TEST(OptimizerTests, TestGetters) EXPECT_EQ(control_seq.vx(0), 342.0); EXPECT_EQ(control_seq.vx.rows(), 30); - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); node->declare_parameter("controller_frequency", rclcpp::ParameterValue(30.0)); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); diff --git a/nav2_mppi_controller/test/parameter_handler_test.cpp b/nav2_mppi_controller/test/parameter_handler_test.cpp index 8752b12968b..61a62e6e483 100644 --- a/nav2_mppi_controller/test/parameter_handler_test.cpp +++ b/nav2_mppi_controller/test/parameter_handler_test.cpp @@ -29,7 +29,7 @@ class ParametersHandlerWrapper : public ParametersHandler ParametersHandlerWrapper() = default; explicit ParametersHandlerWrapper( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name) + const nav2::LifecycleNode::WeakPtr & parent, std::string name) : ParametersHandler(parent, name) {} template @@ -118,7 +118,7 @@ TEST(ParameterHandlerTest, PrePostDynamicCallbackTest) TEST(ParameterHandlerTest, GetSystemParamsTest) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; node->declare_parameter("param1", rclcpp::ParameterValue(true)); node->declare_parameter(name + ".param2", rclcpp::ParameterValue(7)); @@ -142,7 +142,7 @@ TEST(ParameterHandlerTest, GetSystemParamsTest) TEST(ParameterHandlerTest, DynamicAndStaticParametersTest) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); node->declare_parameter("test.dynamic_int", rclcpp::ParameterValue(7)); node->declare_parameter("test.static_int", rclcpp::ParameterValue(7)); @@ -189,7 +189,7 @@ TEST(ParameterHandlerTest, DynamicAndStaticParametersTest) TEST(ParameterHandlerTest, DynamicAndStaticParametersNotVerboseTest) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); node->declare_parameter("test.dynamic_int", rclcpp::ParameterValue(7)); node->declare_parameter("test.static_int", rclcpp::ParameterValue(7)); std::string name = "test"; @@ -235,7 +235,7 @@ TEST(ParameterHandlerTest, DynamicAndStaticParametersNotVerboseTest) TEST(ParameterHandlerTest, DynamicAndStaticParametersNotDeclaredTest) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); node->declare_parameter("test.dynamic_int", rclcpp::ParameterValue(7)); node->declare_parameter("test.static_int", rclcpp::ParameterValue(7)); diff --git a/nav2_mppi_controller/test/path_handler_test.cpp b/nav2_mppi_controller/test/path_handler_test.cpp index 7bec3e0fe44..375978e98da 100644 --- a/nav2_mppi_controller/test/path_handler_test.cpp +++ b/nav2_mppi_controller/test/path_handler_test.cpp @@ -97,7 +97,7 @@ TEST(PathHandlerTests, GetAndPrunePath) TEST(PathHandlerTests, TestBounds) { PathHandlerWrapper handler; - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); node->declare_parameter("dummy.max_robot_pose_search_dist", rclcpp::ParameterValue(99999.9)); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); @@ -149,7 +149,7 @@ TEST(PathHandlerTests, TestBounds) TEST(PathHandlerTests, TestTransforms) { PathHandlerWrapper handler; - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); node->declare_parameter("dummy.max_robot_pose_search_dist", rclcpp::ParameterValue(99999.9)); auto costmap_ros = std::make_shared( "dummy_costmap", "", true); diff --git a/nav2_mppi_controller/test/trajectory_visualizer_tests.cpp b/nav2_mppi_controller/test/trajectory_visualizer_tests.cpp index b78d0e40d4f..7e710fc7375 100644 --- a/nav2_mppi_controller/test/trajectory_visualizer_tests.cpp +++ b/nav2_mppi_controller/test/trajectory_visualizer_tests.cpp @@ -25,7 +25,7 @@ using namespace mppi; // NOLINT TEST(TrajectoryVisualizerTests, StateTransition) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; auto parameters_handler = std::make_unique(node, name); @@ -38,7 +38,7 @@ TEST(TrajectoryVisualizerTests, StateTransition) TEST(TrajectoryVisualizerTests, VisPathRepub) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; auto parameters_handler = std::make_unique(node, name); nav_msgs::msg::Path received_path; @@ -47,7 +47,7 @@ TEST(TrajectoryVisualizerTests, VisPathRepub) pub_path.poses.resize(5); auto my_sub = node->create_subscription( - "~/transformed_global_plan", 10, + "~/transformed_global_plan", [&](const nav_msgs::msg::Path msg) {received_path = msg;}); TrajectoryVisualizer vis; @@ -62,13 +62,13 @@ TEST(TrajectoryVisualizerTests, VisPathRepub) TEST(TrajectoryVisualizerTests, VisOptimalTrajectory) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; auto parameters_handler = std::make_unique(node, name); visualization_msgs::msg::MarkerArray received_msg; auto my_sub = node->create_subscription( - "~/candidate_trajectories", 10, + "~/candidate_trajectories", [&](const visualization_msgs::msg::MarkerArray msg) {received_msg = msg;}); // optimal_trajectory empty, should fail to publish @@ -125,13 +125,13 @@ TEST(TrajectoryVisualizerTests, VisOptimalTrajectory) TEST(TrajectoryVisualizerTests, VisCandidateTrajectories) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; auto parameters_handler = std::make_unique(node, name); visualization_msgs::msg::MarkerArray received_msg; auto my_sub = node->create_subscription( - "~/candidate_trajectories", 10, + "~/candidate_trajectories", [&](const visualization_msgs::msg::MarkerArray msg) {received_msg = msg;}); models::Trajectories candidate_trajectories; @@ -153,7 +153,7 @@ TEST(TrajectoryVisualizerTests, VisCandidateTrajectories) TEST(TrajectoryVisualizerTests, VisOptimalPath) { - auto node = std::make_shared("my_node"); + auto node = std::make_shared("my_node"); std::string name = "test"; auto parameters_handler = std::make_unique(node, name); builtin_interfaces::msg::Time cmd_stamp; @@ -162,7 +162,7 @@ TEST(TrajectoryVisualizerTests, VisOptimalPath) nav_msgs::msg::Path received_path; auto my_sub = node->create_subscription( - "~/optimal_path", 10, + "~/optimal_path", [&](const nav_msgs::msg::Path msg) {received_path = msg;}); // optimal_trajectory empty, should fail to publish diff --git a/nav2_mppi_controller/test/utils/factory.hpp b/nav2_mppi_controller/test/utils/factory.hpp index 804cecb1519..49cba5a82ec 100644 --- a/nav2_mppi_controller/test/utils/factory.hpp +++ b/nav2_mppi_controller/test/utils/factory.hpp @@ -130,20 +130,20 @@ std::shared_ptr getDummyCostmapRos(TestCostmapSet return costmap_ros; } -std::shared_ptr +nav2::LifecycleNode::SharedPtr getDummyNode( TestOptimizerSettings s, std::vector critics, std::string node_name = std::string("dummy")) { auto node = - std::make_shared(node_name, getOptimizerOptions(s, critics)); + std::make_shared(node_name, getOptimizerOptions(s, critics)); return node; } -std::shared_ptr +nav2::LifecycleNode::SharedPtr getDummyNode(rclcpp::NodeOptions options, std::string node_name = std::string("dummy")) { - auto node = std::make_shared(node_name, options); + auto node = std::make_shared(node_name, options); return node; } @@ -153,7 +153,7 @@ std::shared_ptr getDummyOptimizer( TParamHandler * params_handler) { std::shared_ptr optimizer = std::make_shared(); - std::weak_ptr weak_ptr_node{node}; + nav2::LifecycleNode::WeakPtr weak_ptr_node{node}; optimizer->initialize(weak_ptr_node, node->get_name(), costmap_ros, params_handler); @@ -166,7 +166,7 @@ mppi::PathHandler getDummyPathHandler( TParamHandler * params_handler) { mppi::PathHandler path_handler; - std::weak_ptr weak_ptr_node{node}; + nav2::LifecycleNode::WeakPtr weak_ptr_node{node}; path_handler.initialize(weak_ptr_node, node->get_name(), costmap_ros, tf_buffer, params_handler); @@ -179,7 +179,7 @@ std::shared_ptr getDummyController( TCostMap costmap_ros) { auto controller = std::make_shared(); - std::weak_ptr weak_ptr_node{node}; + nav2::LifecycleNode::WeakPtr weak_ptr_node{node}; controller->configure(weak_ptr_node, node->get_name(), tf_buffer, costmap_ros); controller->activate(); diff --git a/nav2_mppi_controller/test/utils/utils.hpp b/nav2_mppi_controller/test/utils/utils.hpp index 1dba6c925d6..b0185ce7cfe 100644 --- a/nav2_mppi_controller/test/utils/utils.hpp +++ b/nav2_mppi_controller/test/utils/utils.hpp @@ -45,7 +45,7 @@ void waitSome(const std::chrono::nanoseconds & duration, TNode & node) void sendTf( std::string_view source, std::string_view dest, std::shared_ptr tf_broadcaster, - std::shared_ptr node, size_t n) + nav2::LifecycleNode::SharedPtr node, size_t n) { while (--n != 0u) { auto t = geometry_msgs::msg::TransformStamped(); diff --git a/nav2_mppi_controller/test/utils_test.cpp b/nav2_mppi_controller/test/utils_test.cpp index 707d9834836..6f70e19cfa5 100644 --- a/nav2_mppi_controller/test/utils_test.cpp +++ b/nav2_mppi_controller/test/utils_test.cpp @@ -32,7 +32,7 @@ class TestGoalChecker : public nav2_core::GoalChecker TestGoalChecker() {} virtual void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & /*parent*/, + const nav2::LifecycleNode::WeakPtr & /*parent*/, const std::string & /*plugin_name*/, const std::shared_ptr/*costmap_ros*/) {} diff --git a/nav2_navfn_planner/CMakeLists.txt b/nav2_navfn_planner/CMakeLists.txt index 478756e2871..07af0e2b19b 100644 --- a/nav2_navfn_planner/CMakeLists.txt +++ b/nav2_navfn_planner/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -26,6 +27,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -76,6 +78,7 @@ ament_export_dependencies( nav2_core nav2_costmap_2d nav2_util + nav2_ros_common nav_msgs rclcpp rclcpp_lifecycle diff --git a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp index 5a1fb19fb99..e7cc28fa781 100644 --- a/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp +++ b/nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp @@ -29,7 +29,7 @@ #include "nav_msgs/msg/path.hpp" #include "nav2_navfn_planner/navfn.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_util/geometry_utils.hpp" @@ -57,7 +57,7 @@ class NavfnPlanner : public nav2_core::GlobalPlanner * @param costmap_ros Costmap2DROS object */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -221,7 +221,7 @@ class NavfnPlanner : public nav2_core::GlobalPlanner bool use_astar_; // parent node weak ptr - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; // Dynamic parameters handler rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; diff --git a/nav2_navfn_planner/package.xml b/nav2_navfn_planner/package.xml index 94e70c2f61c..e00bcefaf29 100644 --- a/nav2_navfn_planner/package.xml +++ b/nav2_navfn_planner/package.xml @@ -22,6 +22,7 @@ rclcpp rclcpp_lifecycle tf2_ros + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_navfn_planner/src/navfn_planner.cpp b/nav2_navfn_planner/src/navfn_planner.cpp index e42c26202a5..fab5d3f0fcf 100644 --- a/nav2_navfn_planner/src/navfn_planner.cpp +++ b/nav2_navfn_planner/src/navfn_planner.cpp @@ -35,12 +35,12 @@ #include "builtin_interfaces/msg/duration.hpp" #include "nav2_navfn_planner/navfn.hpp" #include "nav2_util/costmap.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_costmap_2d/cost_values.hpp" using namespace std::chrono_literals; using namespace std::chrono; // NOLINT -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using rcl_interfaces::msg::ParameterType; using std::placeholders::_1; @@ -61,7 +61,7 @@ NavfnPlanner::~NavfnPlanner() void NavfnPlanner::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) { diff --git a/nav2_navfn_planner/test/test_dynamic_parameters.cpp b/nav2_navfn_planner/test/test_dynamic_parameters.cpp index 543167543ed..844e1d3f2c8 100644 --- a/nav2_navfn_planner/test/test_dynamic_parameters.cpp +++ b/nav2_navfn_planner/test/test_dynamic_parameters.cpp @@ -19,13 +19,13 @@ #include #include "gtest/gtest.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_navfn_planner/navfn_planner.hpp" #include "rclcpp/rclcpp.hpp" TEST(NavfnTest, testDynamicParameter) { - auto node = std::make_shared("Navfntest"); + auto node = std::make_shared("Navfntest"); auto costmap = std::make_shared("global_costmap"); costmap->on_configure(rclcpp_lifecycle::State()); auto planner = diff --git a/nav2_planner/CMakeLists.txt b/nav2_planner/CMakeLists.txt index a5bce30e77f..05e78bc0258 100644 --- a/nav2_planner/CMakeLists.txt +++ b/nav2_planner/CMakeLists.txt @@ -16,6 +16,7 @@ find_package(rclcpp_components REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -29,6 +30,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -93,6 +95,7 @@ ament_export_dependencies( rclcpp rclcpp_lifecycle tf2_ros + nav2_ros_common ) ament_export_targets(${library_name}) ament_package() diff --git a/nav2_planner/include/nav2_planner/planner_server.hpp b/nav2_planner/include/nav2_planner/planner_server.hpp index 21bc032e5fa..c9fc2a46dd6 100644 --- a/nav2_planner/include/nav2_planner/planner_server.hpp +++ b/nav2_planner/include/nav2_planner/planner_server.hpp @@ -25,13 +25,13 @@ #include "geometry_msgs/msg/point.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav_msgs/msg/path.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/action/compute_path_to_pose.hpp" #include "nav2_msgs/action/compute_path_through_poses.hpp" #include "nav2_msgs/msg/costmap.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/simple_action_server.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/simple_action_server.hpp" +#include "nav2_ros_common/service_server.hpp" #include "tf2_ros/transform_listener.h" #include "tf2_ros/create_timer_ros.h" #include "nav2_costmap_2d/costmap_2d_ros.hpp" @@ -49,7 +49,7 @@ namespace nav2_planner * @brief An action server implements the behavior tree's ComputePathToPose * interface and hosts various plugins of different algorithms to compute plans. */ -class PlannerServer : public nav2_util::LifecycleNode +class PlannerServer : public nav2::LifecycleNode { public: /** @@ -84,38 +84,38 @@ class PlannerServer : public nav2_util::LifecycleNode * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activate member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivate member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Reset member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in shutdown state * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; using ActionToPose = nav2_msgs::action::ComputePathToPose; using ActionToPoseResult = ActionToPose::Result; using ActionThroughPoses = nav2_msgs::action::ComputePathThroughPoses; using ActionThroughPosesResult = ActionThroughPoses::Result; - using ActionServerToPose = nav2_util::SimpleActionServer; - using ActionServerThroughPoses = nav2_util::SimpleActionServer; + using ActionServerToPose = nav2::SimpleActionServer; + using ActionServerThroughPoses = nav2::SimpleActionServer; /** * @brief Check if an action server is valid / active @@ -123,7 +123,7 @@ class PlannerServer : public nav2_util::LifecycleNode * @return SUCCESS or FAILURE */ template - bool isServerInactive(std::unique_ptr> & action_server); + bool isServerInactive(typename nav2::SimpleActionServer::SharedPtr & action_server); /** * @brief Check if an action server has a cancellation request pending @@ -131,7 +131,7 @@ class PlannerServer : public nav2_util::LifecycleNode * @return SUCCESS or FAILURE */ template - bool isCancelRequested(std::unique_ptr> & action_server); + bool isCancelRequested(typename nav2::SimpleActionServer::SharedPtr & action_server); /** * @brief Wait for costmap to be valid with updated sensor data or repopulate after a @@ -147,7 +147,7 @@ class PlannerServer : public nav2_util::LifecycleNode */ template void getPreemptedGoalIfRequested( - std::unique_ptr> & action_server, + typename nav2::SimpleActionServer::SharedPtr & action_server, typename std::shared_ptr goal); /** @@ -230,8 +230,8 @@ class PlannerServer : public nav2_util::LifecycleNode dynamicParametersCallback(std::vector parameters); // Our action server implements the ComputePathToPose action - std::unique_ptr action_server_pose_; - std::unique_ptr action_server_poses_; + typename ActionServerToPose::SharedPtr action_server_pose_; + typename ActionServerThroughPoses::SharedPtr action_server_poses_; // Dynamic parameters handler rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; @@ -253,17 +253,16 @@ class PlannerServer : public nav2_util::LifecycleNode // Global Costmap std::shared_ptr costmap_ros_; - std::unique_ptr costmap_thread_; + std::unique_ptr costmap_thread_; nav2_costmap_2d::Costmap2D * costmap_; std::unique_ptr> collision_checker_; // Publishers for the path - rclcpp_lifecycle::LifecyclePublisher::SharedPtr plan_publisher_; + nav2::Publisher::SharedPtr plan_publisher_; // Service to determine if the path is valid - nav2_util::ServiceServer>::SharedPtr is_path_valid_service_; + nav2::ServiceServer::SharedPtr is_path_valid_service_; }; } // namespace nav2_planner diff --git a/nav2_planner/package.xml b/nav2_planner/package.xml index 68d97a5c0d0..b0cdf1c8846 100644 --- a/nav2_planner/package.xml +++ b/nav2_planner/package.xml @@ -23,6 +23,7 @@ rclcpp_lifecycle tf2 tf2_ros + nav2_ros_common ament_cmake_gtest ament_lint_common diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index 15b1001faab..81752e25644 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -26,7 +26,7 @@ #include "lifecycle_msgs/msg/state.hpp" #include "nav2_util/costmap.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_costmap_2d/cost_values.hpp" @@ -40,7 +40,7 @@ namespace nav2_planner { PlannerServer::PlannerServer(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("planner_server", "", options), +: nav2::LifecycleNode("planner_server", "", options), gp_loader_("nav2_core", "nav2_core::GlobalPlanner"), default_ids_{"GridBased"}, default_types_{"nav2_navfn_planner::NavfnPlanner"}, @@ -77,7 +77,7 @@ PlannerServer::~PlannerServer() costmap_thread_.reset(); } -nav2_util::CallbackReturn +nav2::CallbackReturn PlannerServer::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -92,7 +92,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state) } // Launch a thread to run the costmap node - costmap_thread_ = std::make_unique(costmap_ros_); + costmap_thread_ = std::make_unique(costmap_ros_); RCLCPP_DEBUG( get_logger(), "Costmap size: %d,%d", @@ -106,7 +106,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state) for (size_t i = 0; i != planner_ids_.size(); i++) { try { - planner_types_[i] = nav2_util::get_plugin_type_param( + planner_types_[i] = nav2::get_plugin_type_param( node, planner_ids_[i]); nav2_core::GlobalPlanner::Ptr planner = gp_loader_.createUniqueInstance(planner_types_[i]); @@ -120,7 +120,7 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state) get_logger(), "Failed to create global planner. Exception: %s", ex.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } @@ -145,33 +145,31 @@ PlannerServer::on_configure(const rclcpp_lifecycle::State & state) } // Initialize pubs & subs - plan_publisher_ = create_publisher("plan", 1); + plan_publisher_ = create_publisher("plan"); double costmap_update_timeout_dbl; get_parameter("costmap_update_timeout", costmap_update_timeout_dbl); costmap_update_timeout_ = rclcpp::Duration::from_seconds(costmap_update_timeout_dbl); // Create the action servers for path planning to a pose and through poses - action_server_pose_ = std::make_unique( - shared_from_this(), + action_server_pose_ = create_action_server( "compute_path_to_pose", std::bind(&PlannerServer::computePlan, this), nullptr, std::chrono::milliseconds(500), true); - action_server_poses_ = std::make_unique( - shared_from_this(), + action_server_poses_ = create_action_server( "compute_path_through_poses", std::bind(&PlannerServer::computePlanThroughPoses, this), nullptr, std::chrono::milliseconds(500), true); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -181,7 +179,7 @@ PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/) action_server_poses_->activate(); const auto costmap_ros_state = costmap_ros_->activate(); if (costmap_ros_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } PlannerMap::iterator it; @@ -189,26 +187,22 @@ PlannerServer::on_activate(const rclcpp_lifecycle::State & /*state*/) it->second->activate(); } - auto node = shared_from_this(); - - is_path_valid_service_ = std::make_shared>>( + is_path_valid_service_ = create_service( "is_path_valid", - node, std::bind(&PlannerServer::isPathValid, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); // Add callback for dynamic parameters - dyn_params_handler_ = node->add_on_set_parameters_callback( + dyn_params_handler_ = add_on_set_parameters_callback( std::bind(&PlannerServer::dynamicParametersCallback, this, _1)); // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -236,10 +230,10 @@ PlannerServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -260,19 +254,19 @@ PlannerServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) planners_.clear(); costmap_thread_.reset(); costmap_ = nullptr; - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn PlannerServer::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } template bool PlannerServer::isServerInactive( - std::unique_ptr> & action_server) + typename nav2::SimpleActionServer::SharedPtr & action_server) { if (action_server == nullptr || !action_server->is_server_active()) { RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping."); @@ -297,7 +291,7 @@ void PlannerServer::waitForCostmap() template bool PlannerServer::isCancelRequested( - std::unique_ptr> & action_server) + typename nav2::SimpleActionServer::SharedPtr & action_server) { if (action_server->is_cancel_requested()) { RCLCPP_INFO(get_logger(), "Goal was canceled. Canceling planning action."); @@ -310,7 +304,7 @@ bool PlannerServer::isCancelRequested( template void PlannerServer::getPreemptedGoalIfRequested( - std::unique_ptr> & action_server, + typename nav2::SimpleActionServer::SharedPtr & action_server, typename std::shared_ptr goal) { if (action_server->is_preempt_requested()) { @@ -383,13 +377,15 @@ void PlannerServer::computePlanThroughPoses() geometry_msgs::msg::PoseStamped curr_start, curr_goal; try { - if (isServerInactive(action_server_poses_) || isCancelRequested(action_server_poses_)) { + if (isServerInactive(action_server_poses_) || + isCancelRequested(action_server_poses_)) + { return; } waitForCostmap(); - getPreemptedGoalIfRequested(action_server_poses_, goal); + getPreemptedGoalIfRequested(action_server_poses_, goal); if (goal->goals.goals.empty()) { throw nav2_core::NoViapointsGiven("No viapoints given"); @@ -515,13 +511,15 @@ PlannerServer::computePlan() geometry_msgs::msg::PoseStamped start; try { - if (isServerInactive(action_server_pose_) || isCancelRequested(action_server_pose_)) { + if (isServerInactive(action_server_pose_) || + isCancelRequested(action_server_pose_)) + { return; } waitForCostmap(); - getPreemptedGoalIfRequested(action_server_pose_, goal); + getPreemptedGoalIfRequested(action_server_pose_, goal); // Use start pose if provided otherwise use current robot pose if (!getStartPose(goal, start)) { diff --git a/nav2_planner/test/test_dynamic_parameters.cpp b/nav2_planner/test/test_dynamic_parameters.cpp index 61f327e8094..1a773683c0d 100644 --- a/nav2_planner/test/test_dynamic_parameters.cpp +++ b/nav2_planner/test/test_dynamic_parameters.cpp @@ -18,7 +18,7 @@ #include #include "gtest/gtest.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_planner/planner_server.hpp" #include "rclcpp/rclcpp.hpp" #include "rcl_interfaces/msg/set_parameters_result.hpp" diff --git a/nav2_regulated_pure_pursuit_controller/CMakeLists.txt b/nav2_regulated_pure_pursuit_controller/CMakeLists.txt index 91364c36bca..fd8f5fe8f69 100644 --- a/nav2_regulated_pure_pursuit_controller/CMakeLists.txt +++ b/nav2_regulated_pure_pursuit_controller/CMakeLists.txt @@ -16,6 +16,7 @@ find_package(rcl_interfaces REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -30,6 +31,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -84,6 +86,7 @@ ament_export_dependencies( rclcpp rclcpp_lifecycle rcl_interfaces + nav2_ros_common std_msgs tf2 tf2_ros diff --git a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/collision_checker.hpp b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/collision_checker.hpp index baccc6ca20b..c002ee6cb96 100644 --- a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/collision_checker.hpp +++ b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/collision_checker.hpp @@ -21,7 +21,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_costmap_2d/footprint_collision_checker.hpp" #include "nav2_util/odometry_utils.hpp" @@ -29,7 +29,7 @@ #include "nav2_regulated_pure_pursuit_controller/parameter_handler.hpp" #include "nav2_core/controller_exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_costmap_2d/costmap_filters/filter_values.hpp" @@ -47,7 +47,7 @@ class CollisionChecker * @brief Constructor for nav2_regulated_pure_pursuit_controller::CollisionChecker */ CollisionChecker( - rclcpp_lifecycle::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_ros, Parameters * params); /** @@ -96,7 +96,7 @@ class CollisionChecker std::unique_ptr> footprint_collision_checker_; Parameters * params_; - std::shared_ptr> carrot_arc_pub_; + nav2::Publisher::SharedPtr carrot_arc_pub_; rclcpp::Clock::SharedPtr clock_; }; diff --git a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/parameter_handler.hpp b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/parameter_handler.hpp index 3e934ed1f66..2b03443f5fb 100644 --- a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/parameter_handler.hpp +++ b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/parameter_handler.hpp @@ -22,10 +22,10 @@ #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/odometry_utils.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_regulated_pure_pursuit_controller { @@ -76,7 +76,7 @@ class ParameterHandler * @brief Constructor for nav2_regulated_pure_pursuit_controller::ParameterHandler */ ParameterHandler( - rclcpp_lifecycle::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::string & plugin_name, rclcpp::Logger & logger, const double costmap_size_x); @@ -90,7 +90,7 @@ class ParameterHandler Parameters * getParams() {return ¶ms_;} protected: - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; /** * @brief Callback executed when a parameter change is detected * @param event ParameterEvent message diff --git a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp index 1e603f3c8bb..fbab24cc8c7 100644 --- a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp +++ b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/path_handler.hpp @@ -21,7 +21,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_costmap_2d/footprint_collision_checker.hpp" #include "nav2_util/odometry_utils.hpp" diff --git a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp index 2d766ea967f..42ed663d9b3 100644 --- a/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp +++ b/nav2_regulated_pure_pursuit_controller/include/nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp @@ -23,7 +23,7 @@ #include #include "nav2_core/controller.hpp" -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" #include "geometry_msgs/msg/pose2_d.hpp" @@ -61,7 +61,7 @@ class RegulatedPurePursuitController : public nav2_core::Controller * @param costmap_ros Costmap2DROS object of environment */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -207,7 +207,7 @@ class RegulatedPurePursuitController : public nav2_core::Controller */ double findVelocitySignChange(const nav_msgs::msg::Path & transformed_plan); - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; std::shared_ptr tf_; std::string plugin_name_; std::shared_ptr costmap_ros_; @@ -222,14 +222,11 @@ class RegulatedPurePursuitController : public nav2_core::Controller bool is_rotating_to_heading_ = false; bool has_reached_xy_tolerance_ = false; - std::shared_ptr> global_path_pub_; - std::shared_ptr> - carrot_pub_; - std::shared_ptr> - curvature_carrot_pub_; - std::shared_ptr> - is_rotating_to_heading_pub_; - std::shared_ptr> carrot_arc_pub_; + nav2::Publisher::SharedPtr global_path_pub_; + nav2::Publisher::SharedPtr carrot_pub_; + nav2::Publisher::SharedPtr curvature_carrot_pub_; + nav2::Publisher::SharedPtr is_rotating_to_heading_pub_; + nav2::Publisher::SharedPtr carrot_arc_pub_; std::unique_ptr path_handler_; std::unique_ptr param_handler_; std::unique_ptr collision_checker_; diff --git a/nav2_regulated_pure_pursuit_controller/package.xml b/nav2_regulated_pure_pursuit_controller/package.xml index 41b2bade1ee..454b9542c7d 100644 --- a/nav2_regulated_pure_pursuit_controller/package.xml +++ b/nav2_regulated_pure_pursuit_controller/package.xml @@ -24,6 +24,7 @@ std_msgs tf2 tf2_ros + nav2_ros_common ament_cmake_gtest ament_lint_common diff --git a/nav2_regulated_pure_pursuit_controller/src/collision_checker.cpp b/nav2_regulated_pure_pursuit_controller/src/collision_checker.cpp index 89a5a2a1bff..83558bcf4b4 100644 --- a/nav2_regulated_pure_pursuit_controller/src/collision_checker.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/collision_checker.cpp @@ -27,7 +27,7 @@ namespace nav2_regulated_pure_pursuit_controller using namespace nav2_costmap_2d; // NOLINT CollisionChecker::CollisionChecker( - rclcpp_lifecycle::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_ros, Parameters * params) { @@ -41,7 +41,7 @@ CollisionChecker::CollisionChecker( FootprintCollisionChecker>(costmap_); footprint_collision_checker_->setCostmap(costmap_); - carrot_arc_pub_ = node->create_publisher("lookahead_collision_arc", 1); + carrot_arc_pub_ = node->create_publisher("lookahead_collision_arc"); carrot_arc_pub_->on_activate(); } diff --git a/nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp b/nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp index 7a704e6cee0..5bd1f2a7eeb 100644 --- a/nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/parameter_handler.cpp @@ -24,11 +24,11 @@ namespace nav2_regulated_pure_pursuit_controller { -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using rcl_interfaces::msg::ParameterType; ParameterHandler::ParameterHandler( - rclcpp_lifecycle::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::string & plugin_name, rclcpp::Logger & logger, const double costmap_size_x) { diff --git a/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp b/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp index 66b19be3237..1fcc39b7e37 100644 --- a/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/path_handler.cpp @@ -21,7 +21,7 @@ #include "nav2_regulated_pure_pursuit_controller/path_handler.hpp" #include "nav2_core/controller_exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" namespace nav2_regulated_pure_pursuit_controller diff --git a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp index 2f43f427f2f..746dccf48d8 100644 --- a/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp +++ b/nav2_regulated_pure_pursuit_controller/src/regulated_pure_pursuit_controller.cpp @@ -23,7 +23,7 @@ #include "angles/angles.h" #include "nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp" #include "nav2_core/controller_exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_costmap_2d/costmap_filters/filter_values.hpp" @@ -37,7 +37,7 @@ namespace nav2_regulated_pure_pursuit_controller { void RegulatedPurePursuitController::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) { @@ -72,12 +72,12 @@ void RegulatedPurePursuitController::configure( node->get_parameter("controller_frequency", control_frequency); control_duration_ = 1.0 / control_frequency; - global_path_pub_ = node->create_publisher("received_global_plan", 1); - carrot_pub_ = node->create_publisher("lookahead_point", 1); + global_path_pub_ = node->create_publisher("received_global_plan"); + carrot_pub_ = node->create_publisher("lookahead_point"); curvature_carrot_pub_ = node->create_publisher( - "curvature_lookahead_point", 1); + "curvature_lookahead_point"); is_rotating_to_heading_pub_ = node->create_publisher( - "is_rotating_to_heading", 1); + "is_rotating_to_heading"); } void RegulatedPurePursuitController::cleanup() diff --git a/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp b/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp index d25d0a507bf..7639a7ee8bd 100644 --- a/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp +++ b/nav2_regulated_pure_pursuit_controller/test/test_regulated_pp.cpp @@ -21,7 +21,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "path_utils/path_utils.hpp" #include "nav2_regulated_pure_pursuit_controller/regulated_pure_pursuit_controller.hpp" #include "nav2_costmap_2d/costmap_filters/filter_values.hpp" @@ -117,7 +117,7 @@ class BasicAPIRPP : public nav2_regulated_pure_pursuit_controller::RegulatedPure TEST(RegulatedPurePursuitTest, basicAPI) { - auto node = std::make_shared("testRPP"); + auto node = std::make_shared("testRPP"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto costmap = std::make_shared("fake_costmap"); @@ -169,7 +169,7 @@ TEST(RegulatedPurePursuitTest, createCarrotMsg) TEST(RegulatedPurePursuitTest, findVelocitySignChange) { - auto node = std::make_shared("testRPPfindVelocitySignChange"); + auto node = std::make_shared("testRPPfindVelocitySignChange"); auto ctrl = std::make_shared(); std::string name = "PathFollower"; @@ -333,7 +333,7 @@ INSTANTIATE_TEST_SUITE_P( TEST(RegulatedPurePursuitTest, projectCarrotPastGoal) { auto ctrl = std::make_shared(); - auto node = std::make_shared("testRPP"); + auto node = std::make_shared("testRPP"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto costmap = @@ -443,7 +443,7 @@ TEST(RegulatedPurePursuitTest, projectCarrotPastGoal) { TEST(RegulatedPurePursuitTest, lookaheadAPI) { auto ctrl = std::make_shared(); - auto node = std::make_shared("testRPP"); + auto node = std::make_shared("testRPP"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto costmap = std::make_shared("fake_costmap"); @@ -502,8 +502,8 @@ TEST(RegulatedPurePursuitTest, rotateTests) // Non-Stateful Configuration // -------------------------- auto ctrl = std::make_shared(); - auto node = std::make_shared("testRPP"); - nav2_util::declare_parameter_if_not_declared( + auto node = std::make_shared("testRPP"); + nav2::declare_parameter_if_not_declared( node, "PathFollower.stateful", rclcpp::ParameterValue(false)); std::string name = "PathFollower"; @@ -597,7 +597,7 @@ TEST(RegulatedPurePursuitTest, rotateTests) TEST(RegulatedPurePursuitTest, applyConstraints) { auto ctrl = std::make_shared(); - auto node = std::make_shared("testRPP"); + auto node = std::make_shared("testRPP"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto costmap = std::make_shared("fake_costmap"); @@ -605,7 +605,7 @@ TEST(RegulatedPurePursuitTest, applyConstraints) costmap->on_configure(state); constexpr double approach_velocity_scaling_dist = 0.6; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".approach_velocity_scaling_dist", rclcpp::ParameterValue(approach_velocity_scaling_dist)); @@ -697,7 +697,7 @@ TEST(RegulatedPurePursuitTest, applyConstraints) TEST(RegulatedPurePursuitTest, testDynamicParameter) { - auto node = std::make_shared("Smactest"); + auto node = std::make_shared("Smactest"); auto costmap = std::make_shared("global_costmap"); costmap->on_configure(rclcpp_lifecycle::State()); auto ctrl = @@ -799,7 +799,7 @@ class TransformGlobalPlanTest : public ::testing::Test void SetUp() override { ctrl_ = std::make_shared(); - node_ = std::make_shared("testRPP"); + node_ = std::make_shared("testRPP"); costmap_ = std::make_shared("fake_costmap"); tf_buffer_ = std::make_shared(node_->get_clock()); } @@ -828,7 +828,7 @@ class TransformGlobalPlanTest : public ::testing::Test void configure_controller(double max_robot_pose_search_dist) { std::string plugin_name = "test_rpp"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node_, plugin_name + ".max_robot_pose_search_dist", rclcpp::ParameterValue(max_robot_pose_search_dist)); ctrl_->configure(node_, plugin_name, tf_buffer_, costmap_); @@ -873,7 +873,7 @@ class TransformGlobalPlanTest : public ::testing::Test static constexpr char ROBOT_FRAME[] = "test_robot_frame"; std::shared_ptr ctrl_; - std::shared_ptr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr costmap_; std::shared_ptr tf_buffer_; rclcpp::Time transform_time_; diff --git a/nav2_ros_common/CMakeLists.txt b/nav2_ros_common/CMakeLists.txt new file mode 100644 index 00000000000..9bcd37465d9 --- /dev/null +++ b/nav2_ros_common/CMakeLists.txt @@ -0,0 +1,84 @@ +cmake_minimum_required(VERSION 3.5) +project(nav2_ros_common) + +find_package(ament_cmake REQUIRED) +find_package(bond REQUIRED) +find_package(bondcpp REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(lifecycle_msgs REQUIRED) +find_package(nav2_common REQUIRED) +find_package(nav2_msgs REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(rcl_interfaces REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(rclcpp_lifecycle REQUIRED) +find_package(std_msgs REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_geometry_msgs REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(pluginlib REQUIRED) + +nav2_package() + +add_library(${PROJECT_NAME} INTERFACE) +target_include_directories(${PROJECT_NAME} + INTERFACE + "$" + "$" +) + +target_link_libraries(${PROJECT_NAME} INTERFACE + ${geometry_msgs_TARGETS} + ${nav2_msgs_TARGETS} + ${nav_msgs_TARGETS} + ${nav_msgs_TARGETS} + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + rclcpp_action::rclcpp_action + tf2_geometry_msgs::tf2_geometry_msgs + bondcpp::bondcpp +) + +install(DIRECTORY include/ + DESTINATION include/${PROJECT_NAME} +) + +install(TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + + +ament_export_include_directories(include/${PROJECT_NAME}) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + find_package(ament_cmake_pytest REQUIRED) + # skip copyright linting + set(ament_cmake_copyright_FOUND TRUE) + ament_lint_auto_find_test_dependencies() + + find_package(ament_cmake_gtest REQUIRED) + add_subdirectory(test) +endif() + +ament_export_dependencies( + geometry_msgs + nav2_msgs + nav_msgs + rclcpp + rclcpp_action + rclcpp_lifecycle + tf2 + tf2_geometry_msgs + tf2_ros + pluginlib +) + +ament_export_targets(${PROJECT_NAME}) +ament_package() diff --git a/nav2_ros_common/README.md b/nav2_ros_common/README.md new file mode 100644 index 00000000000..084ba6e8f26 --- /dev/null +++ b/nav2_ros_common/README.md @@ -0,0 +1,160 @@ +# Nav2 ROS Common + +This package contains common header-only utilities and definitions used across the Nav2 stack in ROS 2. +These include the Nav2 base Lifecycle Node, Action Server, Service Server, Service Client, Node Thread, and other common components used in Nav2 and related packages. + +The expectation is that all Nav2 nodes and packages use the utilities in this package globally to be consistent and to avoid code duplication. +The lifecycle node includes factories for subscriptions, publishers, clients, and servers that return Nav2 objects in this package rather than the ROS 2 base classes as a level of abstraction of common boilerplate configurations and capabilities. +The factories are listed below: + +- `create_client` --> `nav2::ServiceClient` +- `create_service` --> `nav2::ServiceServer` +- `create_publisher` --> `nav2::Publisher` +- `create_subscriber` --> `nav2::Subscriber` +- `create_action_server` --> `nav2::SimpleActionServer` +- `create_action_client` --> `nav2::ActionClient` + +This is in some cases a big change from `rclcpp` versions, though most have direct analogs or are simply wrappers with additional configurations pre-baked in to remove tedious repetition on every package. +It also allows a central and controlled location to make future changes such as adding tracing, replacing APIs, controlling QoS profiles, or enabling advanced settings. +Thus, see the migration guide below for how to migrate from the previous versions of these objects to the new ones in this package from ROS 2 Kilted to Lyrical. + +## Migration Guide + +To see an example of migration, see the [migration example](https://github.com/ros-navigation/navigation2/pull/5288) of the Nav2 stack. + +### General information + +* `nav2_util::LifecycleNode` is now `nav2::LifecycleNode`, which is largely the same except for the factories and a couple of internal implementation details. +* The Service Client, Service Server, and Simple Action Server were also moved to the `nav2::` namespace, but they should not be accessed directly. Use the `create_*` factories from the `nav2::LifecycleNode`, such as `create_action_server` or `create_action_client`. +* There are now `nav2::qos` profiles for QoS to be used in the codebase for homologation and later easier changing: `nav2::qos::StandardTopicQoS` `nav2::qos::LatchedPublisherQoS`, `nav2::qos::LatchedSubscriberQoS` and `nav2::qos::SensorDataQoS`. These should be used rather than `rclcpp` profiles. +* The APIs for `create_*` are very similar to the default ones, but slightly different to move the now optional QoS profile specification below required information. When this is not specified the `StandardTopicQoS` is used (reliable, queue size 10). Only override this if you want another QoS type -- this is supposed to help make sure that things keep compatible and consistent. Avoid use of `SystemDefaultsQoS`. + +### Plugin Migration + +All plugins now use `nav2::LifecycleNode` instead of `rclcpp_lifecycle::LifecycleNode` or `nav2_util::LifecycleNode`. All must be updated to use this new API from planners and controllers to behavior tree nodes. Similarly, calls to the `create_*` factories will now point to the Nav2 objects, where applicable. See above for what those look like and below for a migration from the existing code usage to the new version in order to make use of the new features and API. + +### Service Client Migration Example + +We no longer need to create the object manually, nor should we as it bypasses the lifecycle node factories that set introspection and other future features. We can use the node now to do this instead of passing in a node and we don't need to specify the node type anymore as a template. +All Nav2 servers should use `nav2::ServiceClient`. + +``` +// If using rclcpp::Client from previous create_client factor +main_client_ = node->create_client(main_srv_name_, rclcpp::SystemDefaultsQoS(), callback_group_); // Type rclcpp:Client + +// If using nav2_util::ServiceClient manually +main_client_ = + std::make_shared>( + main_srv_name_, + node, + false /* Does not create and spin an internal executor*/); // Type nav2_util::ServiceClient +``` + +To: + +``` +main_client_ = node->create_client(main_srv_name_, false /* Does not create and spin an internal executor*/); // Type nav2::ServiceClient +``` + + +### Service Server Migration Example + +Services should now use `nav2::ServiceServer` instead of `rclcpp::Service` or `nav2_util::ServiceServer`. The factory is now available from the node `create_service(...)`, so we can use that to create the service server. +The callback should now include the `rmw_request_id_t` header now, so we have 3 placeholders rather than 2: + +``` +// If using previous create_service factory + service_ = node->create_service( + std::string(node->get_name()) + "/" + getName() + "/reroute", + std::bind( + &ReroutingService::serviceCb, this, + std::placeholders::_1, std::placeholders::_2)); // type rclcpp::Service + +// If using nav2_util::ServiceServer manually + service_ = std::make_shared>>( + std::string(node->get_name()) + "/" + getName() + "/reroute", + node, + std::bind( + &ReroutingService::serviceCb, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); // type nav2_util::ServiceServer + +``` + +To + +``` + service_ = node->create_service( + std::string(node->get_name()) + "/" + getName() + "/reroute", + std::bind(&ReroutingService::serviceCb, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); // type nav2::ServiceServer +``` + +### Action Server Migration + +We can use the factory now from the node and the node is not required as an argument. +This otherwise does not change. +This is analog to the action server but configures with action introspection and other features that are not available in the base `rclcpp_action::Server`. + + +``` + compute_and_track_route_server_ = std::make_shared( + node, "compute_and_track_route", + std::bind(&RouteServer::computeAndTrackRoute, this), + nullptr, std::chrono::milliseconds(500), true); // Type nav2_util::SimpleActionServer +``` + +To + +``` + compute_and_track_route_server_ = create_action_server( + "compute_and_track_route", + std::bind(&RouteServer::computeAndTrackRoute, this), + nullptr, std::chrono::milliseconds(500), true); // Type nav2::SimpleActionServer +``` + +### Action Client Migration + +We can use the node now to create an action client using `create_action_client` without providing all the node interfaces. +This is analog to the action client but configures with action introspection and other features that are not available in the base `rclcpp_action::Client`. + +``` + nav_to_pose_client_ = rclcpp_action::create_client( + get_node_base_interface(), + get_node_graph_interface(), + get_node_logging_interface(), + get_node_waitables_interface(), + "navigate_to_pose", callback_group_); // Type rclcpp_action::Client +``` + +To + +``` + nav_to_pose_client_ = create_action_client( + "navigate_to_pose", callback_group_); // Type nav2::ActionClient +``` + +### Publisher Subscriber Migration + +To migrate, the order of the arguments in the Subscription must change since the QoS profile is now optional. It is now `(topic, callback, QoS)` whereas QoS defaults to the StandardTopicQoS, which is the same as `rclcpp::QoS` for the moment. + +Publishers that explicitly specify a QoS profile do not require changes, though if the constructor using `depth` is used, it must now specify a policy explicitly. Both are now `nav2::Publisher` and `nav2::Subscription` objects that today just typedef the rclcpp and rclcpp_lifecycle versions. In the future, more features will be added here like lifecycle support for the subscriptions, so its highly recommended as part of this migration to migrate the `rclcpp::` to `nav2::` as well so those updates are already easily available. + +``` + plan_publisher_ = create_publisher("plan", 1); + plan_publisher_ = create_publisher("plan", rclcpp::QoS(), callback_group); + + data_sub_ = node->create_subscription( + source_topic, range_qos, + std::bind(&Range::dataCallback, this, std::placeholders::_1)); +``` + +To + +``` + plan_publisher_ = create_publisher("plan"); // No QoS is required if using the StandardTopicQoS, else it can be provided + + data_sub_ = node->create_subscription( + source_topic, + std::bind(&Range::dataCallback, this, std::placeholders::_1)); // QoS can be omitted if using StandardTopicQoS, else it can be provided last +``` diff --git a/nav2_ros_common/include/nav2_ros_common/action_client.hpp b/nav2_ros_common/include/nav2_ros_common/action_client.hpp new file mode 100644 index 00000000000..6ea6590e6a8 --- /dev/null +++ b/nav2_ros_common/include/nav2_ros_common/action_client.hpp @@ -0,0 +1,33 @@ +// Copyright (c) 2025 Open Navigation LLC +// +// 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_ROS_COMMON__ACTION_CLIENT_HPP_ +#define NAV2_ROS_COMMON__ACTION_CLIENT_HPP_ + +#include +#include "rclcpp_action/rclcpp_action.hpp" + +namespace nav2 +{ +/** + * @brief A ROS 2 action client for Nav2 + * This is a convenience type alias to simplify the use of action clients in Nav2 + * which may be further built up on in the future with custom APIs. + */ +template +using ActionClient = rclcpp_action::Client; + +} // namespace nav2 + +#endif // NAV2_ROS_COMMON__ACTION_CLIENT_HPP_ diff --git a/nav2_ros_common/include/nav2_ros_common/interface_factories.hpp b/nav2_ros_common/include/nav2_ros_common/interface_factories.hpp new file mode 100644 index 00000000000..616a9c0acbd --- /dev/null +++ b/nav2_ros_common/include/nav2_ros_common/interface_factories.hpp @@ -0,0 +1,271 @@ +// Copyright (c) 2025 Open Navigation LLC +// +// 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_ROS_COMMON__INTERFACE_FACTORIES_HPP_ +#define NAV2_ROS_COMMON__INTERFACE_FACTORIES_HPP_ + +#include +#include +#include +#include "nav2_ros_common/qos_profiles.hpp" +#include "nav2_ros_common/service_client.hpp" +#include "nav2_ros_common/service_server.hpp" +#include "nav2_ros_common/simple_action_server.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/publisher.hpp" +#include "nav2_ros_common/subscription.hpp" +#include "nav2_ros_common/action_client.hpp" +#include "rclcpp_action/client.hpp" + +namespace nav2 +{ + +namespace interfaces +{ + +/** + * @brief Create a SubscriptionOptions object with Nav2's QoS profiles and options + * @param allow_parameter_qos_overrides Whether to allow QoS overrides for this subscription + * @param callback_group_ptr Pointer to the callback group to use for this subscription + * @param qos_message_lost_callback Callback for when a QoS message is lost + * @param subscription_matched_callback Callback when a subscription is matched with a publisher + * @param incompatible_qos_type_callback Callback for when an incompatible QoS type is requested + * @param qos_requested_incompatible_qos_callback Callback for when a QoS request is incompatible + * @param qos_deadline_requested_callback Callback for when a QoS deadline is missed + * @param qos_liveliness_changed_callback Callback for when a QoS liveliness change occurs + * @return A nav2::SubscriptionOptions object with the specified configurations + */ +inline rclcpp::SubscriptionOptions createSubscriptionOptions( + const bool allow_parameter_qos_overrides = true, + const rclcpp::CallbackGroup::SharedPtr callback_group_ptr = nullptr, + rclcpp::QOSMessageLostCallbackType qos_message_lost_callback = nullptr, + rclcpp::SubscriptionMatchedCallbackType subscription_matched_callback = nullptr, + rclcpp::IncompatibleTypeCallbackType incompatible_qos_type_callback = nullptr, + rclcpp::QOSRequestedIncompatibleQoSCallbackType requested_incompatible_qos_callback = nullptr, + rclcpp::QOSDeadlineRequestedCallbackType qos_deadline_requested_callback = nullptr, + rclcpp::QOSLivelinessChangedCallbackType qos_liveliness_changed_callback = nullptr) +{ + rclcpp::SubscriptionOptions options; + // Allow for all topics to have QoS overrides + if (allow_parameter_qos_overrides) { + options.qos_overriding_options = rclcpp::QosOverridingOptions( + {rclcpp::QosPolicyKind::Depth, rclcpp::QosPolicyKind::Durability, + rclcpp::QosPolicyKind::Reliability, rclcpp::QosPolicyKind::History}); + } + + // Set the callback group to use for this subscription, if given + options.callback_group = callback_group_ptr; + + // Set the event callbacks + options.event_callbacks.deadline_callback = qos_deadline_requested_callback; + options.event_callbacks.liveliness_callback = qos_liveliness_changed_callback; + options.event_callbacks.incompatible_qos_callback = + requested_incompatible_qos_callback; + options.event_callbacks.message_lost_callback = qos_message_lost_callback; + options.event_callbacks.incompatible_type_callback = incompatible_qos_type_callback; + options.event_callbacks.matched_callback = subscription_matched_callback; + return options; +} + +/** + * @brief Create a PublisherOptions object with Nav2's QoS profiles and options + * @param allow_parameter_qos_overrides Whether to allow QoS overrides for this publisher + * @param callback_group_ptr Pointer to the callback group to use for this publisher + * @param publisher_matched_callback Callback when a publisher is matched with a subscriber + * @param incompatible_qos_type_callback Callback for when an incompatible QoS type is requested + * @param offered_incompatible_qos_cb Callback for when a QoS request is incompatible + * @param qos_deadline_offered_callback Callback for when a QoS deadline is missed + * @param qos_liveliness_lost_callback Callback for when a QoS liveliness change occurs + * @return A rclcpp::PublisherOptions object with the specified configurations + */ +inline rclcpp::PublisherOptions createPublisherOptions( + const bool allow_parameter_qos_overrides = true, + const rclcpp::CallbackGroup::SharedPtr callback_group_ptr = nullptr, + rclcpp::PublisherMatchedCallbackType publisher_matched_callback = nullptr, + rclcpp::IncompatibleTypeCallbackType incompatible_qos_type_callback = nullptr, + rclcpp::QOSOfferedIncompatibleQoSCallbackType offered_incompatible_qos_cb = nullptr, + rclcpp::QOSDeadlineOfferedCallbackType qos_deadline_offered_callback = nullptr, + rclcpp::QOSLivelinessLostCallbackType qos_liveliness_lost_callback = nullptr) +{ + rclcpp::PublisherOptions options; + // Allow for all topics to have QoS overrides + if (allow_parameter_qos_overrides) { + options.qos_overriding_options = rclcpp::QosOverridingOptions( + {rclcpp::QosPolicyKind::Depth, rclcpp::QosPolicyKind::Durability, + rclcpp::QosPolicyKind::Reliability, rclcpp::QosPolicyKind::History}); + } + + // Set the callback group to use for this publisher, if given + options.callback_group = callback_group_ptr; + + // Set the event callbacks + options.event_callbacks.deadline_callback = qos_deadline_offered_callback; + options.event_callbacks.liveliness_callback = qos_liveliness_lost_callback; + options.event_callbacks.incompatible_qos_callback = offered_incompatible_qos_cb; + options.event_callbacks.incompatible_type_callback = incompatible_qos_type_callback; + options.event_callbacks.matched_callback = publisher_matched_callback; + return options; +} + +/** + * @brief Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions + * @param node Node to create the subscription on + * @param topic_name Name of topic + * @param callback Callback function to handle incoming messages + * @param qos QoS settings for the subscription (default is nav2::qos::StandardTopicQoS()) + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created subscription + */ +template +typename nav2::Subscription::SharedPtr create_subscription( + const NodeT & node, + const std::string & topic_name, + CallbackT && callback, + const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(), + const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr) +{ + bool allow_parameter_qos_overrides = nav2::declare_or_get_parameter( + node, "allow_parameter_qos_overrides", false); + + auto params_interface = node->get_node_parameters_interface(); + auto topics_interface = node->get_node_topics_interface(); + return rclcpp::create_subscription( + params_interface, + topics_interface, + topic_name, + qos, + std::forward(callback), + createSubscriptionOptions(allow_parameter_qos_overrides, callback_group)); +} + +/** + * @brief Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions + * @param node Node to create the publisher on + * @param topic_name Name of topic + * @param qos QoS settings for the publisher (default is nav2::qos::StandardTopicQoS()) + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created publisher + */ +template +typename nav2::Publisher::SharedPtr create_publisher( + const NodeT & node, + const std::string & topic_name, + const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(), + const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr) +{ + bool allow_parameter_qos_overrides = nav2::declare_or_get_parameter( + node, "allow_parameter_qos_overrides", false); + using PublisherT = nav2::Publisher; + auto pub = rclcpp::create_publisher, PublisherT>( + *node, + topic_name, + qos, + createPublisherOptions(allow_parameter_qos_overrides, callback_group)); + return pub; +} + +/** + * @brief Create a ServiceClient to interface with a service + * @param node Node to create the service client on + * @param service_name Name of service + * @param use_internal_executor Whether to use the internal executor (default is false) + * @return A shared pointer to the created nav2::ServiceClient + */ +template +typename nav2::ServiceClient::SharedPtr create_client( + const NodeT & node, + const std::string & service_name, + bool use_internal_executor = false) +{ + return std::make_shared>( + service_name, node, use_internal_executor); +} + +/** + * @brief Create a ServiceServer to host with a service + * @param node Node to create the service server on + * @param service_name Name of service + * @param callback Callback function to handle service requests + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created nav2::ServiceServer + */ +template +typename nav2::ServiceServer::SharedPtr create_service( + const NodeT & node, + const std::string & service_name, + CallbackT && callback, + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) +{ + using Request = typename SrvT::Request; + using Response = typename SrvT::Response; + using CallbackFn = std::function, + const std::shared_ptr, + std::shared_ptr)>; + CallbackFn cb = std::forward(callback); + + return std::make_shared>( + service_name, node, cb, callback_group); +} + +/** + * @brief Create a SimpleActionServer to host with an action + * @param node Node to create the action server on + * @param action_name Name of action + * @param execute_callback Callback function to handle action execution + * @param completion_callback Callback function to handle action completion (optional) + * @param server_timeout Timeout for the action server (default is 500ms) + * @param spin_thread Whether to spin with a dedicated thread internally (default is false) + * @param realtime Whether the action server's worker thread + * should have elevated prioritization (soft realtime) + * @return A shared pointer to the created nav2::SimpleActionServer + */ +template +typename nav2::SimpleActionServer::SharedPtr create_action_server( + const NodeT & node, + const std::string & action_name, + typename nav2::SimpleActionServer::ExecuteCallback execute_callback, + typename nav2::SimpleActionServer::CompletionCallback complete_cb = nullptr, + std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500), + bool spin_thread = false, + const bool realtime = false) +{ + return std::make_shared>( + node, action_name, execute_callback, complete_cb, server_timeout, spin_thread, realtime); +} + +/** + * @brief Create an action client for a specific action type + * @param node Node to create the action client on + * @param action_name Name of the action + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created nav2::ActionClient + */ +template +typename nav2::ActionClient::SharedPtr create_action_client( + const NodeT & node, + const std::string & action_name, + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) +{ + auto client = rclcpp_action::create_client(node, action_name, callback_group); + nav2::setIntrospectionMode(client, + node->get_node_parameters_interface(), node->get_clock()); + return client; +} + +} // namespace interfaces + +} // namespace nav2 + +#endif // NAV2_ROS_COMMON__INTERFACE_FACTORIES_HPP_ diff --git a/nav2_ros_common/include/nav2_ros_common/lifecycle_node.hpp b/nav2_ros_common/include/nav2_ros_common/lifecycle_node.hpp new file mode 100644 index 00000000000..754f9616253 --- /dev/null +++ b/nav2_ros_common/include/nav2_ros_common/lifecycle_node.hpp @@ -0,0 +1,402 @@ +// Copyright (c) 2025 Open Navigation LLC +// +// 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_ROS_COMMON__LIFECYCLE_NODE_HPP_ +#define NAV2_ROS_COMMON__LIFECYCLE_NODE_HPP_ + +#include +#include +#include +#include +#include +#include + +#include "lifecycle_msgs/msg/state.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "rcl_interfaces/msg/parameter_descriptor.hpp" +#include "nav2_ros_common/node_thread.hpp" +#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "rclcpp/rclcpp.hpp" +#include "bondcpp/bond.hpp" +#include "bond/msg/constants.hpp" +#include "nav2_ros_common/interface_factories.hpp" + +namespace nav2 +{ + +using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; +using namespace std::chrono_literals; // NOLINT + +/** + * @class nav2::LifecycleNode + * @brief A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters + */ +class LifecycleNode : public rclcpp_lifecycle::LifecycleNode +{ +public: + using SharedPtr = std::shared_ptr; + using WeakPtr = std::weak_ptr; + using SharedConstPointer = std::shared_ptr; + + /** + * @brief A lifecycle node constructor + * @param node_name Name for the node + * @param namespace Namespace for the node, if any + * @param options Node options + */ + LifecycleNode( + const std::string & node_name, + const std::string & ns, + const rclcpp::NodeOptions & options = rclcpp::NodeOptions()) + : rclcpp_lifecycle::LifecycleNode(node_name, ns, options) + { + // server side never times out from lifecycle manager + this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true); + this->set_parameter( + rclcpp::Parameter( + bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true)); + + nav2::declare_parameter_if_not_declared( + this, "bond_heartbeat_period", rclcpp::ParameterValue(0.1)); + this->get_parameter("bond_heartbeat_period", bond_heartbeat_period); + + bool autostart_node = false; + nav2::declare_parameter_if_not_declared( + this, "autostart_node", rclcpp::ParameterValue(false)); + this->get_parameter("autostart_node", autostart_node); + if (autostart_node) { + autostart(); + } + + printLifecycleNodeNotification(); + + register_rcl_preshutdown_callback(); + } + + /** + * @brief A lifecycle node constructor with no namespace + * @param node_name Name for the node + * @param options Node options + */ + LifecycleNode( + const std::string & node_name, + const rclcpp::NodeOptions & options = rclcpp::NodeOptions()) + : nav2::LifecycleNode(node_name, "", options) + {} + + virtual ~LifecycleNode() + { + RCLCPP_INFO(get_logger(), "Destroying"); + + runCleanups(); + + if (rcl_preshutdown_cb_handle_) { + rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context(); + context->remove_pre_shutdown_callback(*(rcl_preshutdown_cb_handle_.get())); + rcl_preshutdown_cb_handle_.reset(); + } + } + + /** + * @brief Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions + * @param topic_name Name of topic + * @param callback Callback function to handle incoming messages + * @param qos QoS settings for the subscription (default is nav2::qos::StandardTopicQoS()) + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created nav2::Subscription + */ + template< + typename MessageT, + typename CallbackT> + typename nav2::Subscription::SharedPtr + create_subscription( + const std::string & topic_name, + CallbackT && callback, + const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(), + const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr) + { + return nav2::interfaces::create_subscription( + shared_from_this(), topic_name, + std::forward(callback), qos, callback_group); + } + + /** + * @brief Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions + * @param topic_name Name of topic + * @param qos QoS settings for the publisher (default is nav2::qos::StandardTopicQoS()) + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created nav2::Publisher + */ + template + typename nav2::Publisher::SharedPtr + create_publisher( + const std::string & topic_name, + const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS(), + const rclcpp::CallbackGroup::SharedPtr & callback_group = nullptr) + { + auto pub = nav2::interfaces::create_publisher( + shared_from_this(), topic_name, qos, callback_group); + this->add_managed_entity(pub); + + // Automatically activate the publisher if the node is already active + if (get_current_state().id() == + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + { + pub->on_activate(); + } + + return pub; + } + + /** + * @brief Create a ServiceClient to interface with a service + * @param service_name Name of service + * @param use_internal_executor Whether to use the internal executor (default is false) + * @return A shared pointer to the created nav2::ServiceClient + */ + template + typename nav2::ServiceClient::SharedPtr + create_client( + const std::string & service_name, + bool use_internal_executor = false) + { + return nav2::interfaces::create_client( + shared_from_this(), service_name, use_internal_executor); + } + + /** + * @brief Create a ServiceServer to host with a service + * @param service_name Name of service + * @param callback Callback function to handle service requests + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created nav2::ServiceServer + */ + template + typename nav2::ServiceServer::SharedPtr + create_service( + const std::string & service_name, + typename nav2::ServiceServer::CallbackType cb, + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) + { + return nav2::interfaces::create_service( + shared_from_this(), service_name, cb, callback_group); + } + + /** + * @brief Create a SimpleActionServer to host with an action + * @param action_name Name of action + * @param execute_callback Callback function to handle action execution + * @param completion_callback Callback function to handle action completion (optional) + * @param server_timeout Timeout for the action server (default is 500ms) + * @param spin_thread Whether to spin with a dedicated thread internally (default is false) + * @param realtime Whether the action server's worker thread should have elevated + * @return A shared pointer to the created nav2::SimpleActionServer + */ + template + typename nav2::SimpleActionServer::SharedPtr + create_action_server( + const std::string & action_name, + typename nav2::SimpleActionServer::ExecuteCallback execute_callback, + typename nav2::SimpleActionServer::CompletionCallback compl_cb = nullptr, + std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500), + bool spin_thread = false, + const bool realtime = false) + { + return nav2::interfaces::create_action_server( + shared_from_this(), action_name, execute_callback, + compl_cb, server_timeout, spin_thread, realtime); + } + + /** + * @brief Create a ActionClient to call an action using + * @param action_name Name of action + * @param callback_group The callback group to use (if provided) + * @return A shared pointer to the created nav2::ActionClient + */ + template + typename nav2::ActionClient::SharedPtr + create_action_client( + const std::string & action_name, + rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) + { + return nav2::interfaces::create_action_client( + shared_from_this(), action_name, callback_group); + } + + /** + * @brief Get a shared pointer of this + */ + nav2::LifecycleNode::SharedPtr shared_from_this() + { + return std::static_pointer_cast( + rclcpp_lifecycle::LifecycleNode::shared_from_this()); + } + + /** + * @brief Get a shared pointer of this + */ + nav2::LifecycleNode::WeakPtr weak_from_this() + { + return std::static_pointer_cast( + rclcpp_lifecycle::LifecycleNode::shared_from_this()); + } + + /** + * @brief Abstracted on_error state transition callback, since unimplemented as of 2020 + * in the managed ROS2 node state machine + * @param state State prior to error transition + * @return Return type for success or failed transition to error state + */ + nav2::CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/) + { + RCLCPP_FATAL( + get_logger(), + "Lifecycle node %s does not have error state implemented", get_name()); + return nav2::CallbackReturn::SUCCESS; + } + + /** + * @brief Automatically configure and active the node + */ + void autostart() + { + using lifecycle_msgs::msg::State; + autostart_timer_ = this->create_wall_timer( + 0s, + [this]() -> void { + autostart_timer_->cancel(); + RCLCPP_INFO(get_logger(), "Auto-starting node: %s", this->get_name()); + if (configure().id() != State::PRIMARY_STATE_INACTIVE) { + RCLCPP_ERROR( + get_logger(), "Auto-starting node %s failed to configure!", this->get_name()); + return; + } + if (activate().id() != State::PRIMARY_STATE_ACTIVE) { + RCLCPP_ERROR( + get_logger(), "Auto-starting node %s failed to activate!", this->get_name()); + } + }); + } + + /** + * @brief Perform preshutdown activities before our Context is shutdown. + * Note that this is related to our Context's shutdown sequence, not the + * lifecycle node state machine. + */ + virtual void on_rcl_preshutdown() + { + RCLCPP_INFO( + get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)", + this->get_name()); + + runCleanups(); + + destroyBond(); + } + + /** + * @brief Create bond connection to lifecycle manager + */ + void createBond() + { + if (bond_heartbeat_period > 0.0) { + RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name()); + + bond_ = std::make_unique( + std::string("bond"), + this->get_name(), + shared_from_this()); + + bond_->setHeartbeatPeriod(bond_heartbeat_period); + bond_->setHeartbeatTimeout(4.0); + bond_->start(); + } + } + + /** + * @brief Destroy bond connection to lifecycle manager + */ + void destroyBond() + { + if (bond_heartbeat_period > 0.0) { + RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name()); + + if (bond_) { + bond_.reset(); + } + } + } + +protected: + /** + * @brief Print notifications for lifecycle node + */ + void printLifecycleNodeNotification() + { + RCLCPP_INFO( + get_logger(), + "\n\t%s lifecycle node launched. \n" + "\tWaiting on external lifecycle transitions to activate\n" + "\tSee https://design.ros2.org/articles/node_lifecycle.html for more information.", + get_name()); + } + + /** + * Register our preshutdown callback for this Node's rcl Context. + * The callback fires before this Node's Context is shutdown. + * Note this is not directly related to the lifecycle state machine. + */ + void register_rcl_preshutdown_callback() + { + rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context(); + + rcl_preshutdown_cb_handle_ = std::make_unique( + context->add_pre_shutdown_callback( + std::bind(&LifecycleNode::on_rcl_preshutdown, this)) + ); + } + + /** + * Run some common cleanup steps shared between rcl preshutdown and destruction. + */ + void runCleanups() + { + /* + * In case this lifecycle node wasn't properly shut down, do it here. + * We will give the user some ability to clean up properly here, but it's + * best effort; i.e. we aren't trying to account for all possible states. + */ + if (get_current_state().id() == + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + { + this->deactivate(); + } + + if (get_current_state().id() == + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) + { + this->cleanup(); + } + } + + // Connection to tell that server is still up + std::unique_ptr rcl_preshutdown_cb_handle_{nullptr}; + std::unique_ptr bond_{nullptr}; + double bond_heartbeat_period{0.1}; + rclcpp::TimerBase::SharedPtr autostart_timer_; +}; + +} // namespace nav2 + +#endif // NAV2_ROS_COMMON__LIFECYCLE_NODE_HPP_ diff --git a/nav2_util/include/nav2_util/node_thread.hpp b/nav2_ros_common/include/nav2_ros_common/node_thread.hpp similarity index 70% rename from nav2_util/include/nav2_util/node_thread.hpp rename to nav2_ros_common/include/nav2_ros_common/node_thread.hpp index e0c16927927..6efb43505ab 100644 --- a/nav2_util/include/nav2_util/node_thread.hpp +++ b/nav2_ros_common/include/nav2_ros_common/node_thread.hpp @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAV2_UTIL__NODE_THREAD_HPP_ -#define NAV2_UTIL__NODE_THREAD_HPP_ +#ifndef NAV2_ROS_COMMON__NODE_THREAD_HPP_ +#define NAV2_ROS_COMMON__NODE_THREAD_HPP_ #include #include "rclcpp/rclcpp.hpp" -namespace nav2_util +namespace nav2 { /** - * @class nav2_util::NodeThread + * @class nav2::NodeThread * @brief A background thread to process node/executor callbacks */ class NodeThread @@ -33,14 +33,32 @@ class NodeThread * @param node_base Interface to Node to spin in thread */ explicit NodeThread( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base); + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base) + : node_(node_base) + { + executor_ = std::make_shared(); + thread_ = std::make_unique( + [&]() + { + executor_->add_node(node_); + executor_->spin(); + executor_->remove_node(node_); + }); + } /** * @brief A background thread to process executor's callbacks constructor * @param executor Interface to executor to spin in thread */ explicit NodeThread( - rclcpp::executors::SingleThreadedExecutor::SharedPtr executor); + rclcpp::executors::SingleThreadedExecutor::SharedPtr executor) + : executor_(executor) + { + thread_ = std::make_unique( + [&]() { + executor_->spin(); + }); + } /** * @brief A background thread to process node callbacks constructor @@ -54,7 +72,11 @@ class NodeThread /** * @brief A destructor */ - ~NodeThread(); + ~NodeThread() + { + executor_->cancel(); + thread_->join(); + } protected: rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_; @@ -62,6 +84,6 @@ class NodeThread rclcpp::Executor::SharedPtr executor_; }; -} // namespace nav2_util +} // namespace nav2 -#endif // NAV2_UTIL__NODE_THREAD_HPP_ +#endif // NAV2_ROS_COMMON__NODE_THREAD_HPP_ diff --git a/nav2_util/include/nav2_util/node_utils.hpp b/nav2_ros_common/include/nav2_ros_common/node_utils.hpp similarity index 73% rename from nav2_util/include/nav2_util/node_utils.hpp rename to nav2_ros_common/include/nav2_ros_common/node_utils.hpp index 13bdf907739..6cf10f79d69 100644 --- a/nav2_util/include/nav2_util/node_utils.hpp +++ b/nav2_ros_common/include/nav2_ros_common/node_utils.hpp @@ -13,16 +13,27 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAV2_UTIL__NODE_UTILS_HPP_ -#define NAV2_UTIL__NODE_UTILS_HPP_ +#ifndef NAV2_ROS_COMMON__NODE_UTILS_HPP_ +#define NAV2_ROS_COMMON__NODE_UTILS_HPP_ #include #include +#include +#include +#include +#include "rclcpp/version.h" #include "rclcpp/rclcpp.hpp" #include "rcl_interfaces/srv/list_parameters.hpp" #include "pluginlib/exceptions.hpp" +#include "nav2_ros_common/node_utils.hpp" -namespace nav2_util +using std::chrono::high_resolution_clock; +using std::to_string; +using std::string; +using std::replace_if; +using std::isalnum; + +namespace nav2 { /// Replace invalid characters in a potential node name @@ -35,7 +46,17 @@ namespace nav2_util * \param[in] potential_node_name Potential name but possibly with invalid characters. * \return A copy of the input string but with non-alphanumeric characters replaced with '_' */ -std::string sanitize_node_name(const std::string & potential_node_name); +inline std::string sanitize_node_name(const std::string & potential_node_name) +{ + string node_name(potential_node_name); + // read this as `replace` characters in `node_name` `if` not alphanumeric. + // replace with '_' + replace_if( + begin(node_name), end(node_name), + [](auto c) {return !isalnum(c);}, + '_'); + return node_name; +} /// Concatenate two namespaces to produce an absolute namespace /** @@ -43,7 +64,49 @@ std::string sanitize_node_name(const std::string & potential_node_name); * \param[in] sub_ns The namespace to place after top_ns * \return An absolute namespace starting with "/" */ -std::string add_namespaces(const std::string & top_ns, const std::string & sub_ns = ""); +inline std::string add_namespaces(const std::string & top_ns, const std::string & sub_ns = "") +{ + if (!top_ns.empty() && top_ns.back() == '/') { + if (top_ns.front() == '/') { + return top_ns + sub_ns; + } else { + return "/" + top_ns + sub_ns; + } + } + + return top_ns + "/" + sub_ns; +} + +/// Generates a pseudo random string of digits. +/** + * Generates pseudo random digits by converting the current system time to a + * string. This means that any length more than 8 or so digits will just get + * padded with zeros and doesn't add any additional randomness. + * + * \param[in] len Length of the output string + * \return A string containing random digits + */ +inline std::string time_to_string(size_t len) +{ + string output(len, '0'); // prefill the string with zeros + auto timepoint = high_resolution_clock::now(); + auto timecount = timepoint.time_since_epoch().count(); + auto timestring = to_string(timecount); + if (timestring.length() >= len) { + // if `timestring` is shorter, put it at the end of `output` + output.replace( + 0, len, + timestring, + timestring.length() - len, len); + } else { + // if `output` is shorter, just copy in the end of `timestring` + output.replace( + len - timestring.length(), timestring.length(), + timestring, + 0, timestring.length()); + } + return output; +} /// Add some random characters to a node name to ensure it is unique in the system /** @@ -56,7 +119,10 @@ std::string add_namespaces(const std::string & top_ns, const std::string & sub_n * \param[in] prefix A string to help understand the purpose of the node. * \return A copy of the prefix + '_' + 8 random digits. eg. prefix_12345678 */ -std::string generate_internal_node_name(const std::string & prefix = ""); +inline std::string generate_internal_node_name(const std::string & prefix = "") +{ + return sanitize_node_name(prefix) + "_" + time_to_string(8); +} /// Creates a node with a name as generated by generate_internal_node_name /** @@ -68,18 +134,15 @@ std::string generate_internal_node_name(const std::string & prefix = ""); * \param[in] prefix A string to help understand the purpose of the node. * \return A shared_ptr to the node. */ -rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix = ""); - -/// Generates a pseudo random string of digits. -/** - * Generates pseudo random digits by converting the current system time to a - * string. This means that any length more than 8 or so digits will just get - * padded with zeros and doesn't add any additional randomness. - * - * \param[in] len Length of the output string - * \return A string containing random digits - */ -std::string time_to_string(size_t len); +inline rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix = "") +{ + auto options = + rclcpp::NodeOptions() + .start_parameter_services(false) + .start_parameter_event_publisher(false) + .arguments({"--ros-args", "-r", "__node:=" + generate_internal_node_name(prefix), "--"}); + return rclcpp::Node::make_shared("_", options); +} using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor; @@ -93,7 +156,7 @@ using ParameterDescriptor = rcl_interfaces::msg::ParameterDescriptor; * \param[in] parameter_descriptor Parameter descriptor (optional) */ template -void declare_parameter_if_not_declared( +inline void declare_parameter_if_not_declared( NodeT node, const std::string & parameter_name, const rclcpp::ParameterValue & default_value, @@ -113,7 +176,7 @@ void declare_parameter_if_not_declared( * \param[in] parameter_descriptor Parameter descriptor (optional) */ template -void declare_parameter_if_not_declared( +inline void declare_parameter_if_not_declared( NodeT node, const std::string & parameter_name, const rclcpp::ParameterType & param_type, @@ -137,7 +200,7 @@ void declare_parameter_if_not_declared( * \return The value of the parameter or an exception */ template -ParameterT declare_or_get_parameter( +inline ParameterT declare_or_get_parameter( NodeT node, const std::string & parameter_name, const rclcpp::ParameterType & param_type, @@ -173,7 +236,7 @@ using NodeParamInterfacePtr = rclcpp::node_interfaces::NodeParametersInterface:: * \return The value of the param from the override if existent, otherwise the default value */ template -ParamType declare_or_get_parameter( +inline ParamType declare_or_get_parameter( const rclcpp::Logger & logger, NodeParamInterfacePtr param_interface, const std::string & parameter_name, const ParamType & default_value, bool warn_if_no_override = false, bool strict_param_loading = false, @@ -224,7 +287,7 @@ ParamType declare_or_get_parameter( * \return The value of the param from the override if existent, otherwise the default value */ template -ParamType declare_or_get_parameter( +inline ParamType declare_or_get_parameter( NodeT node, const std::string & parameter_name, const ParamType & default_value, const ParameterDescriptor & parameter_descriptor = ParameterDescriptor()) @@ -249,7 +312,7 @@ ParamType declare_or_get_parameter( * \return A string containing the type of plugin (the value of ".plugin" parameter) */ template -std::string get_plugin_type_param( +inline std::string get_plugin_type_param( NodeT node, const std::string & plugin_name) { @@ -274,8 +337,47 @@ std::string get_plugin_type_param( * increasing the priority level of the host thread. * May throw exception if unable to set prioritization successfully */ -void setSoftRealTimePriority(); +inline void setSoftRealTimePriority() +{ + sched_param sch; + sch.sched_priority = 49; + if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) { + std::string errmsg( + "Cannot set as real-time thread. Users must set: hard rtprio 99 and " + " soft rtprio 99 in /etc/security/limits.conf to enable " + "realtime prioritization! Error: "); + throw std::runtime_error(errmsg + std::strerror(errno)); + } +} + +template +inline void setIntrospectionMode( + InterfaceT & ros_interface, + rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface, + rclcpp::Clock::SharedPtr clock) +{ + #if RCLCPP_VERSION_GTE(29, 0, 0) + rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF; + if (!node_parameters_interface->has_parameter("service_introspection_mode")) { + node_parameters_interface->declare_parameter( + "service_introspection_mode", rclcpp::ParameterValue("disabled")); + } + std::string service_introspection_mode = + node_parameters_interface->get_parameter("service_introspection_mode").as_string(); + if (service_introspection_mode == "metadata") { + introspection_state = RCL_SERVICE_INTROSPECTION_METADATA; + } else if (service_introspection_mode == "contents") { + introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS; + } + + ros_interface->configure_introspection(clock, rclcpp::ServicesQoS(), introspection_state); + #else + (void)ros_interface; + (void)node_parameters_interface; + (void)clock; + #endif +} -} // namespace nav2_util +} // namespace nav2 -#endif // NAV2_UTIL__NODE_UTILS_HPP_ +#endif // NAV2_ROS_COMMON__NODE_UTILS_HPP_ diff --git a/nav2_ros_common/include/nav2_ros_common/publisher.hpp b/nav2_ros_common/include/nav2_ros_common/publisher.hpp new file mode 100644 index 00000000000..144e1dac3bd --- /dev/null +++ b/nav2_ros_common/include/nav2_ros_common/publisher.hpp @@ -0,0 +1,33 @@ +// Copyright (c) 2025 Open Navigation LLC +// +// 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_ROS_COMMON__PUBLISHER_HPP_ +#define NAV2_ROS_COMMON__PUBLISHER_HPP_ + +#include +#include "rclcpp_lifecycle/lifecycle_publisher.hpp" + +namespace nav2 +{ +/** + * @brief A ROS 2 publisher for Nav2 + * This is a convenience type alias to simplify the use of publishers in Nav2 + * which may be further built up on in the future with custom APIs. + */ +template +using Publisher = rclcpp_lifecycle::LifecyclePublisher; + +} // namespace nav2 + +#endif // NAV2_ROS_COMMON__PUBLISHER_HPP_ diff --git a/nav2_ros_common/include/nav2_ros_common/qos_profiles.hpp b/nav2_ros_common/include/nav2_ros_common/qos_profiles.hpp new file mode 100644 index 00000000000..42ef6309126 --- /dev/null +++ b/nav2_ros_common/include/nav2_ros_common/qos_profiles.hpp @@ -0,0 +1,110 @@ +// Copyright (c) 2025 Open Navigation LLC +// +// 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_ROS_COMMON__QOS_PROFILES_HPP_ +#define NAV2_ROS_COMMON__QOS_PROFILES_HPP_ + +#include "rclcpp/rclcpp.hpp" + +namespace nav2 +{ + +namespace qos +{ + +/** + * @class nav2::qos::StandardTopicQoS + * @brief A QoS profile for standard reliable topics with a history of 10 messages + */ +class StandardTopicQoS : public rclcpp::QoS +{ +public: + /** + * @brief Constructor for StandardTopicQoS + * @param depth The history depth for the QoS profile, default is 10 + */ + explicit + StandardTopicQoS(const int depth = 10) // NOLINT + : rclcpp::QoS(rclcpp::KeepLast(depth)) + { + this->reliable(); + this->durability_volatile(); + } +}; + +/** + * @class nav2::qos::LatchedPublisherQoS + * @brief A QoS profile for latched, reliable topics with a history of 1 messages + */ +class LatchedPublisherQoS : public rclcpp::QoS +{ +public: + /** + * @brief Constructor for LatchedPublisherQoS + * @param depth The history depth for the QoS profile, default is 1 + */ + explicit + LatchedPublisherQoS(const int depth = 1) // NOLINT + : rclcpp::QoS(rclcpp::KeepLast(depth)) + { + this->reliable(); + this->transient_local(); + } +}; + +/** + * @class nav2::qos::LatchedSubscriptionQoS + * @brief A QoS profile for latched, reliable topics with a history of 1 messages + */ +class LatchedSubscriptionQoS : public rclcpp::QoS +{ +public: + /** + * @brief Constructor for LatchedSubscriptionQoS + * @param depth The history depth for the QoS profile, default is 1 + */ + explicit + LatchedSubscriptionQoS(const int depth = 10) // NOLINT + : rclcpp::QoS(rclcpp::KeepLast(depth)) + { + this->reliable(); + this->transient_local(); + } +}; + +/** + * @class nav2::qos::SensorDataQoS + * @brief A QoS profile for best-effort sensor data with a history of 10 messages + */ +class SensorDataQoS : public rclcpp::QoS +{ +public: + /** + * @brief Constructor for SensorDataQoS + * @param depth The history depth for the QoS profile, default is 10 + */ + explicit + SensorDataQoS(const int depth = 10) // NOLINT + : rclcpp::QoS(rclcpp::KeepLast(depth)) + { + this->best_effort(); + this->durability_volatile(); + } +}; + +} // namespace qos + +} // namespace nav2 + +#endif // NAV2_ROS_COMMON__QOS_PROFILES_HPP_ diff --git a/nav2_util/include/nav2_util/service_client.hpp b/nav2_ros_common/include/nav2_ros_common/service_client.hpp similarity index 72% rename from nav2_util/include/nav2_util/service_client.hpp rename to nav2_ros_common/include/nav2_ros_common/service_client.hpp index 5d8ffcbe99b..c1bc2bd8435 100644 --- a/nav2_util/include/nav2_util/service_client.hpp +++ b/nav2_ros_common/include/nav2_ros_common/service_client.hpp @@ -12,68 +12,68 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAV2_UTIL__SERVICE_CLIENT_HPP_ -#define NAV2_UTIL__SERVICE_CLIENT_HPP_ +#ifndef NAV2_ROS_COMMON__SERVICE_CLIENT_HPP_ +#define NAV2_ROS_COMMON__SERVICE_CLIENT_HPP_ #include #include #include #include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/node_utils.hpp" -namespace nav2_util +namespace nav2 { /** - * @class nav2_util::ServiceClient + * @class nav2::ServiceClient * @brief A simple wrapper on ROS2 services client */ -template +template class ServiceClient { public: + using SharedPtr = std::shared_ptr>; + using UniquePtr = std::unique_ptr>; + /** * @brief A constructor * @param service_name name of the service to call * @param provided_node Node to create the service client off of * @param use_internal_executor Whether to create an internal executor or not */ + template explicit ServiceClient( const std::string & service_name, const NodeT & provided_node, bool use_internal_executor = false) - : service_name_(service_name), node_(provided_node), use_internal_executor_(use_internal_executor) + : service_name_(service_name), + clock_(provided_node->get_clock()), + logger_(provided_node->get_logger()), + node_base_interface_(provided_node->get_node_base_interface()), + use_internal_executor_(use_internal_executor) { if (use_internal_executor) { - callback_group_ = node_->create_callback_group( + callback_group_ = provided_node->create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_ = std::make_shared(); callback_group_executor_->add_callback_group(callback_group_, - node_->get_node_base_interface()); + provided_node->get_node_base_interface()); } // When a nullptr is passed, the client will use the default callback group - client_ = node_->template create_client( + client_ = rclcpp::create_client( + provided_node->get_node_base_interface(), + provided_node->get_node_graph_interface(), + provided_node->get_node_services_interface(), service_name, - rclcpp::SystemDefaultsQoS(), + rclcpp::ServicesQoS(), // Use consistent QoS settings callback_group_); - rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF; - if (!node_->has_parameter("service_introspection_mode")) { - node_->declare_parameter("service_introspection_mode", "disabled"); - } - std::string service_introspection_mode = - node_->get_parameter("service_introspection_mode").as_string(); - if (service_introspection_mode == "metadata") { - introspection_state = RCL_SERVICE_INTROSPECTION_METADATA; - } else if (service_introspection_mode == "contents") { - introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS; - } - this->client_->configure_introspection( - node_->get_clock(), rclcpp::SystemDefaultsQoS(), introspection_state); + nav2::setIntrospectionMode(this->client_, + provided_node->get_node_parameters_interface(), clock_); } using RequestType = typename ServiceT::Request; using ResponseType = typename ServiceT::Response; - using SharedPtr = std::shared_ptr>; /** * @brief Invoke the service and block until completed or timed out @@ -83,20 +83,27 @@ class ServiceClient */ typename ResponseType::SharedPtr invoke( typename RequestType::SharedPtr & request, - const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)) + const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1), + const std::chrono::nanoseconds wait_for_service_timeout = std::chrono::seconds(10)) { + auto now = clock_->now(); while (!client_->wait_for_service(std::chrono::seconds(1))) { if (!rclcpp::ok()) { throw std::runtime_error( service_name_ + " service client: interrupted while waiting for service"); } RCLCPP_INFO( - node_->get_logger(), "%s service client: waiting for service to appear...", + logger_, "%s service client: waiting for service to appear...", service_name_.c_str()); + + if (clock_->now() - now > wait_for_service_timeout) { + throw std::runtime_error( + service_name_ + " service client: timed out waiting for service"); + } } RCLCPP_DEBUG( - node_->get_logger(), "%s service client: send async request", + logger_, "%s service client: send async request", service_name_.c_str()); auto future_result = client_->async_send_request(request); if (spin_until_complete(future_result, timeout) != rclcpp::FutureReturnCode::SUCCESS) { @@ -116,20 +123,27 @@ class ServiceClient */ bool invoke( typename RequestType::SharedPtr & request, - typename ResponseType::SharedPtr & response) + typename ResponseType::SharedPtr & response, + const std::chrono::nanoseconds wait_for_service_timeout = std::chrono::seconds(10)) { + auto now = clock_->now(); while (!client_->wait_for_service(std::chrono::seconds(1))) { if (!rclcpp::ok()) { throw std::runtime_error( service_name_ + " service client: interrupted while waiting for service"); } RCLCPP_INFO( - node_->get_logger(), "%s service client: waiting for service to appear...", + logger_, "%s service client: waiting for service to appear...", service_name_.c_str()); + + if (clock_->now() - now > wait_for_service_timeout) { + throw std::runtime_error( + service_name_ + " service client: timed out waiting for service"); + } } RCLCPP_DEBUG( - node_->get_logger(), "%s service client: send async request", + logger_, "%s service client: send async request", service_name_.c_str()); auto future_result = client_->async_send_request(request); if (spin_until_complete(future_result) != rclcpp::FutureReturnCode::SUCCESS) { @@ -191,7 +205,7 @@ class ServiceClient if (use_internal_executor_) { return callback_group_executor_->spin_until_future_complete(future, timeout); } else { - return rclcpp::spin_until_future_complete(node_, future, timeout); + return rclcpp::spin_until_future_complete(node_base_interface_, future, timeout); } } @@ -206,13 +220,15 @@ class ServiceClient protected: std::string service_name_; - NodeT node_; + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_{rclcpp::get_logger("nav2_ros_common")}; + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_; rclcpp::CallbackGroup::SharedPtr callback_group_{nullptr}; rclcpp::executors::SingleThreadedExecutor::SharedPtr callback_group_executor_; typename rclcpp::Client::SharedPtr client_; bool use_internal_executor_; }; -} // namespace nav2_util +} // namespace nav2 -#endif // NAV2_UTIL__SERVICE_CLIENT_HPP_ +#endif // NAV2_ROS_COMMON__SERVICE_CLIENT_HPP_ diff --git a/nav2_util/include/nav2_util/service_server.hpp b/nav2_ros_common/include/nav2_ros_common/service_server.hpp similarity index 59% rename from nav2_util/include/nav2_util/service_server.hpp rename to nav2_ros_common/include/nav2_ros_common/service_server.hpp index acdc374a9ea..7e16a671736 100644 --- a/nav2_util/include/nav2_util/service_server.hpp +++ b/nav2_ros_common/include/nav2_ros_common/service_server.hpp @@ -12,22 +12,23 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAV2_UTIL__SERVICE_SERVER_HPP_ -#define NAV2_UTIL__SERVICE_SERVER_HPP_ +#ifndef NAV2_ROS_COMMON__SERVICE_SERVER_HPP_ +#define NAV2_ROS_COMMON__SERVICE_SERVER_HPP_ #include #include #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" -namespace nav2_util +namespace nav2 { /** - * @class nav2_util::ServiceServer + * @class nav2::ServiceServer * @brief A simple wrapper on ROS2 services server */ -template +template class ServiceServer { public: @@ -35,39 +36,30 @@ class ServiceServer using ResponseType = typename ServiceT::Response; using CallbackType = std::function, const std::shared_ptr, std::shared_ptr)>; - using SharedPtr = std::shared_ptr>; + using SharedPtr = std::shared_ptr>; + using UniquePtr = std::unique_ptr>; + template explicit ServiceServer( const std::string & service_name, const NodeT & node, CallbackType callback, - const rclcpp::QoS & qos = rclcpp::ServicesQoS(), rclcpp::CallbackGroup::SharedPtr callback_group = nullptr) : service_name_(service_name), callback_(callback) { - server_ = node->template create_service( + server_ = rclcpp::create_service( + node->get_node_base_interface(), + node->get_node_services_interface(), service_name, [this](const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response) { this->callback_(request_header, request, response); }, - qos, + rclcpp::ServicesQoS(), // Use consistent QoS settings callback_group); - rcl_service_introspection_state_t introspection_state = RCL_SERVICE_INTROSPECTION_OFF; - if(!node->has_parameter("service_introspection_mode")) { - node->declare_parameter("service_introspection_mode", "disabled"); - } - std::string service_introspection_mode = - node->get_parameter("service_introspection_mode").as_string(); - if (service_introspection_mode == "metadata") { - introspection_state = RCL_SERVICE_INTROSPECTION_METADATA; - } else if (service_introspection_mode == "contents") { - introspection_state = RCL_SERVICE_INTROSPECTION_CONTENTS; - } - - this->server_->configure_introspection( - node->get_clock(), rclcpp::SystemDefaultsQoS(), introspection_state); + nav2::setIntrospectionMode(this->server_, + node->get_node_parameters_interface(), node->get_clock()); } protected: @@ -76,7 +68,7 @@ class ServiceServer typename rclcpp::Service::SharedPtr server_; }; -} // namespace nav2_util +} // namespace nav2 -#endif // NAV2_UTIL__SERVICE_SERVER_HPP_ +#endif // NAV2_ROS_COMMON__SERVICE_SERVER_HPP_ diff --git a/nav2_util/include/nav2_util/simple_action_server.hpp b/nav2_ros_common/include/nav2_ros_common/simple_action_server.hpp similarity index 94% rename from nav2_util/include/nav2_util/simple_action_server.hpp rename to nav2_ros_common/include/nav2_ros_common/simple_action_server.hpp index c595b838dc5..e0722598545 100644 --- a/nav2_util/include/nav2_util/simple_action_server.hpp +++ b/nav2_ros_common/include/nav2_ros_common/simple_action_server.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_ -#define NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_ +#ifndef NAV2_ROS_COMMON__SIMPLE_ACTION_SERVER_HPP_ +#define NAV2_ROS_COMMON__SIMPLE_ACTION_SERVER_HPP_ #include #include @@ -25,20 +25,23 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_action.hpp" -#include "nav2_util/node_thread.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_thread.hpp" +#include "nav2_ros_common/node_utils.hpp" -namespace nav2_util +namespace nav2 { /** - * @class nav2_util::SimpleActionServer + * @class nav2::SimpleActionServer * @brief An action server wrapper to make applications simpler using Actions */ template class SimpleActionServer { public: + using SharedPtr = std::shared_ptr>; + using UniquePtr = std::unique_ptr>; + // Callback function to complete main work. This should itself deal with its // own exceptions, but if for some reason one is thrown, it will be caught // in SimpleActionServer and terminate the action itself. @@ -58,7 +61,6 @@ class SimpleActionServer * @param execute_callback Execution callback function of Action * @param server_timeout Timeout to to react to stop or preemption requests * @param spin_thread Whether to spin with a dedicated thread internally - * @param options Options to pass to the underlying rcl_action_server_t * @param realtime Whether the action server's worker thread should have elevated * prioritization (soft realtime) */ @@ -70,15 +72,15 @@ class SimpleActionServer CompletionCallback completion_callback = nullptr, std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500), bool spin_thread = false, - const rcl_action_server_options_t & options = rcl_action_server_get_default_options(), const bool realtime = false) : SimpleActionServer( node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(), node->get_node_waitables_interface(), + node->get_node_parameters_interface(), action_name, execute_callback, completion_callback, - server_timeout, spin_thread, options, realtime) + server_timeout, spin_thread, realtime) {} /** @@ -88,7 +90,6 @@ class SimpleActionServer * @param execute_callback Execution callback function of Action * @param server_timeout Timeout to to react to stop or preemption requests * @param spin_thread Whether to spin with a dedicated thread internally - * @param options Options to pass to the underlying rcl_action_server_t * @param realtime Whether the action server's worker thread should have elevated * prioritization (soft realtime) */ @@ -97,17 +98,18 @@ class SimpleActionServer rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, + rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface, const std::string & action_name, ExecuteCallback execute_callback, CompletionCallback completion_callback = nullptr, std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500), bool spin_thread = false, - const rcl_action_server_options_t & options = rcl_action_server_get_default_options(), const bool realtime = false) : node_base_interface_(node_base_interface), node_clock_interface_(node_clock_interface), node_logging_interface_(node_logging_interface), node_waitables_interface_(node_waitables_interface), + node_parameters_interface_(node_parameters_interface), action_name_(action_name), execute_callback_(execute_callback), completion_callback_(completion_callback), @@ -129,12 +131,16 @@ class SimpleActionServer std::bind(&SimpleActionServer::handle_goal, this, _1, _2), std::bind(&SimpleActionServer::handle_cancel, this, _1), std::bind(&SimpleActionServer::handle_accepted, this, _1), - options, + rcl_action_server_get_default_options(), // Use consistent QoS settings callback_group_); + + nav2::setIntrospectionMode(this->action_server_, + node_parameters_interface_, node_clock_interface_->get_clock()); + if (spin_thread_) { executor_ = std::make_shared(); executor_->add_callback_group(callback_group_, node_base_interface_); - executor_thread_ = std::make_unique(executor_); + executor_thread_ = std::make_unique(executor_); } } @@ -190,7 +196,7 @@ class SimpleActionServer void setSoftRealTimePriority() { if (use_realtime_prioritization_) { - nav2_util::setSoftRealTimePriority(); + nav2::setSoftRealTimePriority(); debug_msg("Soft realtime prioritization successfully set!"); } } @@ -532,6 +538,7 @@ class SimpleActionServer rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface_; rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface_; rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface_; + rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface_; std::string action_name_; ExecuteCallback execute_callback_; @@ -552,7 +559,7 @@ class SimpleActionServer bool spin_thread_; rclcpp::CallbackGroup::SharedPtr callback_group_{nullptr}; rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; - std::unique_ptr executor_thread_; + std::unique_ptr executor_thread_; /** * @brief Generate an empty result object for an action type @@ -668,6 +675,6 @@ class SimpleActionServer } }; -} // namespace nav2_util +} // namespace nav2 -#endif // NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_ +#endif // NAV2_ROS_COMMON__SIMPLE_ACTION_SERVER_HPP_ diff --git a/nav2_ros_common/include/nav2_ros_common/subscription.hpp b/nav2_ros_common/include/nav2_ros_common/subscription.hpp new file mode 100644 index 00000000000..b6b5bf64f0c --- /dev/null +++ b/nav2_ros_common/include/nav2_ros_common/subscription.hpp @@ -0,0 +1,34 @@ +// Copyright (c) 2025 Open Navigation LLC +// +// 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_ROS_COMMON__SUBSCRIPTION_HPP_ +#define NAV2_ROS_COMMON__SUBSCRIPTION_HPP_ + +#include +#include "rclcpp/rclcpp.hpp" + +namespace nav2 +{ + +/** + * @brief A ROS 2 subscription for Nav2 + * This is a convenience type alias to simplify the use of subscriptions in Nav2 + * which may be further built up on in the future with custom APIs. + */ +template +using Subscription = rclcpp::Subscription; + +} // namespace nav2 + +#endif // NAV2_ROS_COMMON__SUBSCRIPTION_HPP_ diff --git a/nav2_util/include/nav2_util/validate_messages.hpp b/nav2_ros_common/include/nav2_ros_common/validate_messages.hpp similarity index 96% rename from nav2_util/include/nav2_util/validate_messages.hpp rename to nav2_ros_common/include/nav2_ros_common/validate_messages.hpp index 315f05fee05..392d3622ed0 100644 --- a/nav2_util/include/nav2_util/validate_messages.hpp +++ b/nav2_ros_common/include/nav2_ros_common/validate_messages.hpp @@ -13,8 +13,8 @@ // limitations under the License. -#ifndef NAV2_UTIL__VALIDATE_MESSAGES_HPP_ -#define NAV2_UTIL__VALIDATE_MESSAGES_HPP_ +#ifndef NAV2_ROS_COMMON__VALIDATE_MESSAGES_HPP_ +#define NAV2_ROS_COMMON__VALIDATE_MESSAGES_HPP_ #include #include @@ -40,7 +40,7 @@ // like the size of `map` should be equal to `height*width` // 3> Any other needed condition could be joint here in future -namespace nav2_util +namespace nav2 { @@ -172,8 +172,6 @@ bool validateMsg(const nav_msgs::msg::OccupancyGrid & msg) return true; } +} // namespace nav2 -} // namespace nav2_util - - -#endif // NAV2_UTIL__VALIDATE_MESSAGES_HPP_ +#endif // NAV2_ROS_COMMON__VALIDATE_MESSAGES_HPP_ diff --git a/nav2_ros_common/package.xml b/nav2_ros_common/package.xml new file mode 100644 index 00000000000..33731f20e15 --- /dev/null +++ b/nav2_ros_common/package.xml @@ -0,0 +1,42 @@ + + + + nav2_ros_common + 1.4.0 + Nav2 utilities + Steve Macenski + Apache-2.0 + + ament_cmake + + nav2_common + + bond + bondcpp + builtin_interfaces + geometry_msgs + lifecycle_msgs + nav2_msgs + nav_msgs + rcl_interfaces + rclcpp + rclcpp_action + rclcpp_lifecycle + std_msgs + tf2 + tf2_geometry_msgs + tf2_msgs + tf2_ros + pluginlib + + ament_lint_common + ament_lint_auto + ament_cmake_gtest + std_srvs + test_msgs + ament_cmake_pytest + + + ament_cmake + + diff --git a/nav2_ros_common/test/CMakeLists.txt b/nav2_ros_common/test/CMakeLists.txt new file mode 100644 index 00000000000..05eb8a9fbfd --- /dev/null +++ b/nav2_ros_common/test/CMakeLists.txt @@ -0,0 +1,127 @@ +find_package(std_srvs REQUIRED) +find_package(test_msgs REQUIRED) + +ament_add_gtest(test_node_utils test_node_utils.cpp) +target_include_directories(test_node_utils PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/../include +) +target_link_libraries(test_node_utils + bondcpp::bondcpp + ${geometry_msgs_TARGETS} + ${lifecycle_msgs_TARGETS} + ${nav2_msgs_TARGETS} + ${nav_msgs_TARGETS} + ${rcl_interfaces_TARGETS} + rclcpp::rclcpp + rclcpp_action::rclcpp_action + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + tf2::tf2 + ${tf2_geometry_msgs_TARGETS} + pluginlib::pluginlib +) + +ament_add_gtest(test_service_client test_service_client.cpp) +target_include_directories(test_service_client PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/../include +) +target_link_libraries(test_service_client + bondcpp::bondcpp + ${geometry_msgs_TARGETS} + ${lifecycle_msgs_TARGETS} + ${nav2_msgs_TARGETS} + ${nav_msgs_TARGETS} + ${rcl_interfaces_TARGETS} + rclcpp::rclcpp + rclcpp_action::rclcpp_action + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + tf2::tf2 + ${tf2_geometry_msgs_TARGETS} + pluginlib::pluginlib + ${std_srvs_TARGETS} +) + +ament_add_gtest(test_service_server test_service_server.cpp) +target_include_directories(test_service_server PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/../include +) +target_link_libraries(test_service_server + bondcpp::bondcpp + ${geometry_msgs_TARGETS} + ${lifecycle_msgs_TARGETS} + ${nav2_msgs_TARGETS} + ${nav_msgs_TARGETS} + ${rcl_interfaces_TARGETS} + rclcpp::rclcpp + rclcpp_action::rclcpp_action + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + tf2::tf2 + ${tf2_geometry_msgs_TARGETS} + pluginlib::pluginlib + ${std_srvs_TARGETS} +) + +ament_add_gtest(test_actions test_actions.cpp) +target_include_directories(test_actions PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/../include +) +target_link_libraries(test_actions + bondcpp::bondcpp + ${geometry_msgs_TARGETS} + ${lifecycle_msgs_TARGETS} + ${nav2_msgs_TARGETS} + ${nav_msgs_TARGETS} + ${rcl_interfaces_TARGETS} + rclcpp::rclcpp + rclcpp_action::rclcpp_action + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + tf2::tf2 + ${tf2_geometry_msgs_TARGETS} + pluginlib::pluginlib + ${test_msgs_TARGETS} +) + +ament_add_gtest(test_lifecycle_node test_lifecycle_node.cpp) +target_include_directories(test_lifecycle_node PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/../include +) +target_link_libraries(test_lifecycle_node + bondcpp::bondcpp + ${geometry_msgs_TARGETS} + ${lifecycle_msgs_TARGETS} + ${nav2_msgs_TARGETS} + ${nav_msgs_TARGETS} + ${rcl_interfaces_TARGETS} + rclcpp::rclcpp + rclcpp_action::rclcpp_action + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + tf2::tf2 + ${tf2_geometry_msgs_TARGETS} + pluginlib::pluginlib +) + +ament_add_gtest(test_validation_messages test_validation_messages.cpp) +target_include_directories(test_validation_messages PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR}/../include +) +target_link_libraries(test_validation_messages + bondcpp::bondcpp + ${geometry_msgs_TARGETS} + ${lifecycle_msgs_TARGETS} + ${nav2_msgs_TARGETS} + ${nav_msgs_TARGETS} + ${rcl_interfaces_TARGETS} + rclcpp::rclcpp + rclcpp_action::rclcpp_action + rclcpp_lifecycle::rclcpp_lifecycle + tf2_ros::tf2_ros + tf2::tf2 + ${tf2_geometry_msgs_TARGETS} + pluginlib::pluginlib + ${builtin_interfaces_TARGETS} + ${std_msgs_TARGETS} +) diff --git a/nav2_util/test/test_actions.cpp b/nav2_ros_common/test/test_actions.cpp similarity index 95% rename from nav2_util/test/test_actions.cpp rename to nav2_ros_common/test/test_actions.cpp index 1482fbe0fa1..7da319e4e2e 100644 --- a/nav2_util/test/test_actions.cpp +++ b/nav2_ros_common/test/test_actions.cpp @@ -17,8 +17,7 @@ #include #include "gtest/gtest.h" -#include "nav2_util/node_utils.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "test_msgs/action/fibonacci.hpp" #include "std_msgs/msg/empty.hpp" @@ -42,7 +41,7 @@ class FibonacciServerNode : public rclcpp::Node void on_init() { - action_server_ = std::make_shared>( + action_server_ = std::make_shared>( shared_from_this(), "fibonacci", std::bind(&FibonacciServerNode::execute, this)); @@ -136,10 +135,10 @@ class FibonacciServerNode : public rclcpp::Node } private: - std::shared_ptr> action_server_; - rclcpp::Subscription::SharedPtr deactivate_subs_; - rclcpp::Subscription::SharedPtr activate_subs_; - rclcpp::Subscription::SharedPtr omit_preempt_subs_; + nav2::SimpleActionServer::SharedPtr action_server_; + nav2::Subscription::SharedPtr deactivate_subs_; + nav2::Subscription::SharedPtr activate_subs_; + nav2::Subscription::SharedPtr omit_preempt_subs_; bool do_premptions_{true}; }; @@ -192,7 +191,7 @@ class ActionTestNode : public rclcpp::Node { public: ActionTestNode() - : rclcpp::Node(nav2_util::generate_internal_node_name("action_test_node")) + : rclcpp::Node(nav2::generate_internal_node_name("action_test_node")) { } @@ -229,7 +228,7 @@ class ActionTestNode : public rclcpp::Node omit_prempt_pub_->publish(std_msgs::msg::Empty()); } - rclcpp_action::Client::SharedPtr action_client_; + nav2::ActionClient::SharedPtr action_client_; rclcpp::Publisher::SharedPtr deactivate_pub_; rclcpp::Publisher::SharedPtr activate_pub_; rclcpp::Publisher::SharedPtr omit_prempt_pub_; @@ -311,7 +310,7 @@ TEST_F(ActionTest, test_simple_action_with_feedback) auto goal = Fibonacci::Goal(); goal.order = 10; - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); send_goal_options.feedback_callback = feedback_callback; // Send the goal diff --git a/nav2_util/test/test_lifecycle_node.cpp b/nav2_ros_common/test/test_lifecycle_node.cpp similarity index 78% rename from nav2_util/test/test_lifecycle_node.cpp rename to nav2_ros_common/test/test_lifecycle_node.cpp index d29da5e6df4..2a1a2cf5e32 100644 --- a/nav2_util/test/test_lifecycle_node.cpp +++ b/nav2_ros_common/test/test_lifecycle_node.cpp @@ -15,7 +15,7 @@ #include #include "gtest/gtest.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" class RclCppFixture @@ -26,21 +26,21 @@ class RclCppFixture }; RclCppFixture g_rclcppfixture; -class LifecycleTransitionTestNode : public nav2_util::LifecycleNode +class LifecycleTransitionTestNode : public nav2::LifecycleNode { public: explicit LifecycleTransitionTestNode(rclcpp::NodeOptions options) - : nav2_util::LifecycleNode("test_node", "", options) {} + : nav2::LifecycleNode("test_node", "", options) {} - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &) override + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &) override { configured = true; - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &) override { activated = true; - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool configured{false}; @@ -54,7 +54,7 @@ class LifecycleTransitionTestNode : public nav2_util::LifecycleNode TEST(LifecycleNode, RclcppNodeExitsCleanly) { // Make sure the node exits cleanly when using an rclcpp_node and associated thread - auto node1 = std::make_shared("test_node", ""); + auto node1 = std::make_shared("test_node", ""); std::this_thread::sleep_for(std::chrono::seconds(1)); SUCCEED(); } @@ -62,8 +62,8 @@ TEST(LifecycleNode, RclcppNodeExitsCleanly) TEST(LifecycleNode, MultipleRclcppNodesExitCleanly) { // Try a couple nodes w/ rclcpp_node and threads - auto node1 = std::make_shared("test_node1", ""); - auto node2 = std::make_shared("test_node2", ""); + auto node1 = std::make_shared("test_node1", ""); + auto node2 = std::make_shared("test_node2", ""); std::this_thread::sleep_for(std::chrono::seconds(1)); SUCCEED(); @@ -97,12 +97,12 @@ TEST(LifecycleNode, OnPreshutdownCbFires) { // Ensure the on_rcl_preshutdown_cb fires - class MyNodeType : public nav2_util::LifecycleNode + class MyNodeType : public nav2::LifecycleNode { public: MyNodeType( const std::string & node_name) - : nav2_util::LifecycleNode(node_name) {} + : nav2::LifecycleNode(node_name, rclcpp::NodeOptions()) {} bool fired = false; @@ -111,7 +111,7 @@ TEST(LifecycleNode, OnPreshutdownCbFires) { fired = true; - nav2_util::LifecycleNode::on_rcl_preshutdown(); + nav2::LifecycleNode::on_rcl_preshutdown(); } }; diff --git a/nav2_util/test/test_node_utils.cpp b/nav2_ros_common/test/test_node_utils.cpp similarity index 92% rename from nav2_util/test/test_node_utils.cpp rename to nav2_ros_common/test/test_node_utils.cpp index 2c7814fae1d..6a3177993d2 100644 --- a/nav2_util/test/test_node_utils.cpp +++ b/nav2_ros_common/test/test_node_utils.cpp @@ -15,18 +15,18 @@ #include #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -using nav2_util::sanitize_node_name; -using nav2_util::generate_internal_node_name; -using nav2_util::generate_internal_node; -using nav2_util::add_namespaces; -using nav2_util::time_to_string; -using nav2_util::declare_parameter_if_not_declared; -using nav2_util::declare_or_get_parameter; -using nav2_util::get_plugin_type_param; +using nav2::sanitize_node_name; +using nav2::generate_internal_node_name; +using nav2::generate_internal_node; +using nav2::add_namespaces; +using nav2::time_to_string; +using nav2::declare_parameter_if_not_declared; +using nav2::declare_or_get_parameter; +using nav2::get_plugin_type_param; TEST(SanitizeNodeName, SanitizeNodeName) { diff --git a/nav2_util/test/test_service_client.cpp b/nav2_ros_common/test/test_service_client.cpp similarity index 95% rename from nav2_util/test/test_service_client.cpp rename to nav2_ros_common/test/test_service_client.cpp index 7ee89331274..cc6e779964c 100644 --- a/nav2_util/test/test_service_client.cpp +++ b/nav2_ros_common/test/test_service_client.cpp @@ -14,13 +14,13 @@ #include #include -#include "nav2_util/service_client.hpp" +#include "nav2_ros_common/service_client.hpp" #include "rclcpp/rclcpp.hpp" #include "std_srvs/srv/empty.hpp" #include "std_msgs/msg/empty.hpp" #include "gtest/gtest.h" -using nav2_util::ServiceClient; +using nav2::ServiceClient; using std::string; class RclCppFixture @@ -41,8 +41,7 @@ class TestServiceClient : public ServiceClient : ServiceClient(name, provided_node, use_internal_executor) {} - string name() {return node_->get_name();} - const rclcpp::Node::SharedPtr & getNode() {return node_;} + string name() {return node_base_interface_->get_name();} }; TEST(ServiceClient, can_ServiceClient_use_passed_in_node) @@ -54,7 +53,6 @@ TEST(ServiceClient, can_ServiceClient_use_passed_in_node) auto node = rclcpp::Node::make_shared("test_node" + mode); node->declare_parameter("service_introspection_mode", mode); TestServiceClient t("bar", node, true); - ASSERT_EQ(t.getNode(), node); ASSERT_EQ(t.name(), "test_node" + mode); } } diff --git a/nav2_util/test/test_service_server.cpp b/nav2_ros_common/test/test_service_server.cpp similarity index 97% rename from nav2_util/test/test_service_server.cpp rename to nav2_ros_common/test/test_service_server.cpp index 582f047259c..336d1c459a4 100644 --- a/nav2_util/test/test_service_server.cpp +++ b/nav2_ros_common/test/test_service_server.cpp @@ -14,13 +14,13 @@ #include #include -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/service_server.hpp" #include "rclcpp/rclcpp.hpp" #include "std_srvs/srv/empty.hpp" #include "std_msgs/msg/empty.hpp" #include "gtest/gtest.h" -using nav2_util::ServiceServer; +using nav2::ServiceServer; using std::string; class RclCppFixture diff --git a/nav2_util/test/test_validation_messages.cpp b/nav2_ros_common/test/test_validation_messages.cpp similarity index 84% rename from nav2_util/test/test_validation_messages.cpp rename to nav2_ros_common/test/test_validation_messages.cpp index a7d8ed89041..1a47ec2142b 100644 --- a/nav2_util/test/test_validation_messages.cpp +++ b/nav2_ros_common/test/test_validation_messages.cpp @@ -13,15 +13,15 @@ // limitations under the License. #include -#include "nav2_util/validate_messages.hpp" +#include "nav2_ros_common/validate_messages.hpp" TEST(ValidateMessagesTest, DoubleValueCheck) { // Test valid double value - EXPECT_TRUE(nav2_util::validateMsg(3.14)); + EXPECT_TRUE(nav2::validateMsg(3.14)); // Test invalid double value (infinity) - EXPECT_FALSE(nav2_util::validateMsg(std::numeric_limits::infinity())); + EXPECT_FALSE(nav2::validateMsg(std::numeric_limits::infinity())); // Test invalid double value (NaN) - EXPECT_FALSE(nav2_util::validateMsg(std::numeric_limits::quiet_NaN())); + EXPECT_FALSE(nav2::validateMsg(std::numeric_limits::quiet_NaN())); } TEST(ValidateMessagesTest, TimeStampCheck) @@ -30,12 +30,12 @@ TEST(ValidateMessagesTest, TimeStampCheck) builtin_interfaces::msg::Time valid_time_stamp; valid_time_stamp.sec = 123; valid_time_stamp.nanosec = 456789; - EXPECT_TRUE(nav2_util::validateMsg(valid_time_stamp)); + EXPECT_TRUE(nav2::validateMsg(valid_time_stamp)); // Test invalid time stamp (nanosec out of range) builtin_interfaces::msg::Time invalid_time_stamp; invalid_time_stamp.sec = 123; invalid_time_stamp.nanosec = 1e9; // 1 second = 1e9 nanoseconds - EXPECT_FALSE(nav2_util::validateMsg(invalid_time_stamp)); + EXPECT_FALSE(nav2::validateMsg(invalid_time_stamp)); } TEST(ValidateMessagesTest, HeaderCheck) @@ -45,17 +45,17 @@ TEST(ValidateMessagesTest, HeaderCheck) valid_header.stamp.sec = 123; valid_header.stamp.nanosec = 456789; valid_header.frame_id = "map"; - EXPECT_TRUE(nav2_util::validateMsg(valid_header)); + EXPECT_TRUE(nav2::validateMsg(valid_header)); // Test invalid header with empty frame_id std_msgs::msg::Header invalid_header; invalid_header.stamp.sec = 123; invalid_header.stamp.nanosec = 456789; invalid_header.frame_id = ""; - EXPECT_FALSE(nav2_util::validateMsg(invalid_header)); + EXPECT_FALSE(nav2::validateMsg(invalid_header)); invalid_header.stamp.sec = 123; invalid_header.stamp.nanosec = 1e9; invalid_header.frame_id = "map"; - EXPECT_FALSE(nav2_util::validateMsg(invalid_header)); + EXPECT_FALSE(nav2::validateMsg(invalid_header)); } TEST(ValidateMessagesTest, PointCheck) @@ -65,23 +65,23 @@ TEST(ValidateMessagesTest, PointCheck) valid_point.x = 1.0; valid_point.y = 2.0; valid_point.z = 3.0; - EXPECT_TRUE(nav2_util::validateMsg(valid_point)); + EXPECT_TRUE(nav2::validateMsg(valid_point)); // Test invalid Point message with NaN value geometry_msgs::msg::Point invalid_point; invalid_point.x = 1.0; invalid_point.y = std::numeric_limits::quiet_NaN(); invalid_point.z = 3.0; - EXPECT_FALSE(nav2_util::validateMsg(invalid_point)); + EXPECT_FALSE(nav2::validateMsg(invalid_point)); // Test invalid Point message with NaN value invalid_point.x = std::numeric_limits::quiet_NaN(); invalid_point.y = 2.0; invalid_point.z = 3.0; - EXPECT_FALSE(nav2_util::validateMsg(invalid_point)); + EXPECT_FALSE(nav2::validateMsg(invalid_point)); // Test invalid Point message with NaN value invalid_point.x = 1.0; invalid_point.y = 2.0; invalid_point.z = std::numeric_limits::quiet_NaN(); - EXPECT_FALSE(nav2_util::validateMsg(invalid_point)); + EXPECT_FALSE(nav2::validateMsg(invalid_point)); } TEST(ValidateMessagesTest, QuaternionCheck) @@ -92,36 +92,36 @@ TEST(ValidateMessagesTest, QuaternionCheck) valid_quaternion.y = 0.0; valid_quaternion.z = 0.0; valid_quaternion.w = 1.0; - EXPECT_TRUE(nav2_util::validateMsg(valid_quaternion)); + EXPECT_TRUE(nav2::validateMsg(valid_quaternion)); // Test invalid Quaternion message with invalid magnitude geometry_msgs::msg::Quaternion invalid_quaternion; invalid_quaternion.x = 0.1; invalid_quaternion.y = 0.2; invalid_quaternion.z = 0.3; invalid_quaternion.w = 0.5; // Invalid magnitude (should be 1.0) - EXPECT_FALSE(nav2_util::validateMsg(invalid_quaternion)); + EXPECT_FALSE(nav2::validateMsg(invalid_quaternion)); // One NaN value invalid_quaternion.x = 0.0; invalid_quaternion.y = std::numeric_limits::quiet_NaN(); invalid_quaternion.z = 0.0; invalid_quaternion.w = 1.0; - EXPECT_FALSE(nav2_util::validateMsg(invalid_quaternion)); + EXPECT_FALSE(nav2::validateMsg(invalid_quaternion)); invalid_quaternion.x = std::numeric_limits::quiet_NaN(); invalid_quaternion.y = 0.0; invalid_quaternion.z = 0.0; invalid_quaternion.w = 1.0; - EXPECT_FALSE(nav2_util::validateMsg(invalid_quaternion)); + EXPECT_FALSE(nav2::validateMsg(invalid_quaternion)); invalid_quaternion.x = 0.0; invalid_quaternion.y = 0.0; invalid_quaternion.z = std::numeric_limits::quiet_NaN(); invalid_quaternion.w = 1.0; - EXPECT_FALSE(nav2_util::validateMsg(invalid_quaternion)); + EXPECT_FALSE(nav2::validateMsg(invalid_quaternion)); invalid_quaternion.x = 0.0; invalid_quaternion.y = 0.0; invalid_quaternion.z = 1.0; invalid_quaternion.w = std::numeric_limits::quiet_NaN(); - EXPECT_FALSE(nav2_util::validateMsg(invalid_quaternion)); + EXPECT_FALSE(nav2::validateMsg(invalid_quaternion)); } TEST(ValidateMessagesTest, PoseCheck) @@ -135,7 +135,7 @@ TEST(ValidateMessagesTest, PoseCheck) valid_pose.orientation.y = 0.0; valid_pose.orientation.z = 0.0; valid_pose.orientation.w = 0.0; - EXPECT_TRUE(nav2_util::validateMsg(valid_pose)); + EXPECT_TRUE(nav2::validateMsg(valid_pose)); // Test invalid Pose message with invalid position geometry_msgs::msg::Pose invalid_pose; invalid_pose.position.x = 1.0; @@ -145,7 +145,7 @@ TEST(ValidateMessagesTest, PoseCheck) invalid_pose.orientation.y = 0.0; invalid_pose.orientation.z = 0.0; invalid_pose.orientation.w = 0.0; - EXPECT_FALSE(nav2_util::validateMsg(invalid_pose)); + EXPECT_FALSE(nav2::validateMsg(invalid_pose)); // Test invalid Pose message with invalid orientation invalid_pose.position.x = 1.0; invalid_pose.position.y = 2.0; @@ -154,7 +154,7 @@ TEST(ValidateMessagesTest, PoseCheck) invalid_pose.orientation.y = 0.2; invalid_pose.orientation.z = 0.3; invalid_pose.orientation.w = 0.4; - EXPECT_FALSE(nav2_util::validateMsg(invalid_pose)); + EXPECT_FALSE(nav2::validateMsg(invalid_pose)); } @@ -173,7 +173,7 @@ TEST(ValidateMessagesTest, MapMetaDataCheck) { valid_origin.orientation.z = 0.0; valid_origin.orientation.w = 1.0; valid_map_meta_data.origin = valid_origin; - EXPECT_TRUE(nav2_util::validateMsg(valid_map_meta_data)); + EXPECT_TRUE(nav2::validateMsg(valid_map_meta_data)); // Test invalid origin message nav_msgs::msg::MapMetaData invalid_map_meta_data; @@ -189,21 +189,21 @@ TEST(ValidateMessagesTest, MapMetaDataCheck) { invalid_origin.orientation.z = 1.0; invalid_origin.orientation.w = 1.0; invalid_map_meta_data.origin = invalid_origin; - EXPECT_FALSE(nav2_util::validateMsg(invalid_map_meta_data)); + EXPECT_FALSE(nav2::validateMsg(invalid_map_meta_data)); // Test invalid resolution message invalid_map_meta_data.resolution = std::numeric_limits::quiet_NaN(); invalid_map_meta_data.width = 100; invalid_map_meta_data.height = 100; invalid_map_meta_data.origin = valid_origin; - EXPECT_FALSE(nav2_util::validateMsg(invalid_map_meta_data)); + EXPECT_FALSE(nav2::validateMsg(invalid_map_meta_data)); // Test invalid MapMetaData message with zero width invalid_map_meta_data.resolution = 0.05; invalid_map_meta_data.width = 0; invalid_map_meta_data.height = 100; invalid_map_meta_data.origin = valid_origin; - EXPECT_FALSE(nav2_util::validateMsg(invalid_map_meta_data)); + EXPECT_FALSE(nav2::validateMsg(invalid_map_meta_data)); } TEST(ValidateMessagesTest, OccupancyGridCheck) { @@ -215,7 +215,7 @@ TEST(ValidateMessagesTest, OccupancyGridCheck) { valid_occupancy_grid.info.height = 100; std::vector data(100 * 100, 0); // Initialize with zeros valid_occupancy_grid.data = data; - EXPECT_TRUE(nav2_util::validateMsg(valid_occupancy_grid)); + EXPECT_TRUE(nav2::validateMsg(valid_occupancy_grid)); // Test invalid header message with wrong data size nav_msgs::msg::OccupancyGrid invalid_occupancy_grid; @@ -224,7 +224,7 @@ TEST(ValidateMessagesTest, OccupancyGridCheck) { invalid_occupancy_grid.info.width = 100; invalid_occupancy_grid.info.height = 100; invalid_occupancy_grid.data = data; - EXPECT_FALSE(nav2_util::validateMsg(invalid_occupancy_grid)); + EXPECT_FALSE(nav2::validateMsg(invalid_occupancy_grid)); // Test invalid info message with wrong data size invalid_occupancy_grid.header.frame_id = "map"; @@ -232,7 +232,7 @@ TEST(ValidateMessagesTest, OccupancyGridCheck) { invalid_occupancy_grid.info.width = 0; // Incorrect width invalid_occupancy_grid.info.height = 100; invalid_occupancy_grid.data = data; - EXPECT_FALSE(nav2_util::validateMsg(invalid_occupancy_grid)); + EXPECT_FALSE(nav2::validateMsg(invalid_occupancy_grid)); // Test invalid OccupancyGrid message with wrong data size invalid_occupancy_grid.header.frame_id = "map"; @@ -241,7 +241,7 @@ TEST(ValidateMessagesTest, OccupancyGridCheck) { invalid_occupancy_grid.info.height = 100; std::vector invalid_data(100 * 99, 0); // Incorrect data size invalid_occupancy_grid.data = invalid_data; - EXPECT_FALSE(nav2_util::validateMsg(invalid_occupancy_grid)); + EXPECT_FALSE(nav2::validateMsg(invalid_occupancy_grid)); } TEST(ValidateMessagesTest, PoseWithCovarianceCheck) { @@ -260,7 +260,7 @@ TEST(ValidateMessagesTest, PoseWithCovarianceCheck) { validate_msg.pose.orientation.z = 0.0; validate_msg.pose.orientation.w = -0.32979028309372299; - EXPECT_TRUE(nav2_util::validateMsg(validate_msg)); + EXPECT_TRUE(nav2::validateMsg(validate_msg)); // Invalid messages geometry_msgs::msg::PoseWithCovariance invalidate_msg1; @@ -279,7 +279,7 @@ TEST(ValidateMessagesTest, PoseWithCovarianceCheck) { invalidate_msg1.pose.orientation.z = 0.0; invalidate_msg1.pose.orientation.w = -0.32979028309372299; - EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg1)); + EXPECT_FALSE(nav2::validateMsg(invalidate_msg1)); geometry_msgs::msg::PoseWithCovariance invalidate_msg2; invalidate_msg2.covariance[0] = 0.25; @@ -295,7 +295,7 @@ TEST(ValidateMessagesTest, PoseWithCovarianceCheck) { invalidate_msg2.pose.orientation.z = 0.0; invalidate_msg2.pose.orientation.w = -0.32979028309372299; - EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg2)); + EXPECT_FALSE(nav2::validateMsg(invalidate_msg2)); } TEST(ValidateMessagesTest, PoseWithCovarianceStampedCheck) { @@ -318,7 +318,7 @@ TEST(ValidateMessagesTest, PoseWithCovarianceStampedCheck) { validate_msg.pose.pose.orientation.z = 0.0; validate_msg.pose.pose.orientation.w = -0.32979028309372299; - EXPECT_TRUE(nav2_util::validateMsg(validate_msg)); + EXPECT_TRUE(nav2::validateMsg(validate_msg)); // Invalid messages geometry_msgs::msg::PoseWithCovarianceStamped invalidate_msg1; @@ -341,7 +341,7 @@ TEST(ValidateMessagesTest, PoseWithCovarianceStampedCheck) { invalidate_msg1.pose.pose.orientation.z = 0.0; invalidate_msg1.pose.pose.orientation.w = -0.32979028309372299; - EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg1)); + EXPECT_FALSE(nav2::validateMsg(invalidate_msg1)); geometry_msgs::msg::PoseWithCovarianceStamped invalidate_msg2; invalidate_msg2.header.frame_id = ""; @@ -361,7 +361,7 @@ TEST(ValidateMessagesTest, PoseWithCovarianceStampedCheck) { invalidate_msg2.pose.pose.orientation.z = 0.0; invalidate_msg2.pose.pose.orientation.w = -0.32979028309372299; - EXPECT_FALSE(nav2_util::validateMsg(invalidate_msg2)); + EXPECT_FALSE(nav2::validateMsg(invalidate_msg2)); } diff --git a/nav2_rotation_shim_controller/CMakeLists.txt b/nav2_rotation_shim_controller/CMakeLists.txt index 3323d3d767a..e7f40238000 100644 --- a/nav2_rotation_shim_controller/CMakeLists.txt +++ b/nav2_rotation_shim_controller/CMakeLists.txt @@ -16,6 +16,7 @@ find_package(rclcpp_lifecycle REQUIRED) find_package(rcl_interfaces REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -27,6 +28,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -78,6 +80,7 @@ ament_export_dependencies( rclcpp_lifecycle rcl_interfaces tf2_ros + nav2_ros_common ) ament_export_targets(${library_name}) diff --git a/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp b/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp index b5e16edf8c4..5f12c6dda68 100644 --- a/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp +++ b/nav2_rotation_shim_controller/include/nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp @@ -58,7 +58,7 @@ class RotationShimController : public nav2_core::Controller * @param costmap_ros Costmap2DROS object of environment */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -169,7 +169,7 @@ class RotationShimController : public nav2_core::Controller rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector parameters); - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; + nav2::LifecycleNode::WeakPtr node_; std::shared_ptr tf_; std::string plugin_name_; rclcpp::Logger logger_ {rclcpp::get_logger("RotationShimController")}; diff --git a/nav2_rotation_shim_controller/package.xml b/nav2_rotation_shim_controller/package.xml index 87a7f0ec1bd..2505599a071 100644 --- a/nav2_rotation_shim_controller/package.xml +++ b/nav2_rotation_shim_controller/package.xml @@ -23,6 +23,7 @@ rcl_interfaces tf2 tf2_ros + nav2_ros_common ament_cmake_gtest ament_lint_common diff --git a/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp b/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp index f3081c9cd05..5be66f548ac 100644 --- a/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp +++ b/nav2_rotation_shim_controller/src/nav2_rotation_shim_controller.cpp @@ -20,7 +20,7 @@ #include "angles/angles.h" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp" @@ -39,7 +39,7 @@ RotationShimController::RotationShimController() } void RotationShimController::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) { @@ -56,27 +56,27 @@ void RotationShimController::configure( std::string primary_controller; double control_frequency; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".angular_dist_threshold", rclcpp::ParameterValue(0.785)); // 45 deg - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".angular_disengage_threshold", rclcpp::ParameterValue(0.785 / 2.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".forward_sampling_distance", rclcpp::ParameterValue(0.5)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".rotate_to_heading_angular_vel", rclcpp::ParameterValue(1.8)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".max_angular_accel", rclcpp::ParameterValue(3.2)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".simulate_ahead_time", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".primary_controller", rclcpp::PARAMETER_STRING); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".rotate_to_goal_heading", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".rotate_to_heading_once", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".closed_loop", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name_ + ".use_path_orientations", rclcpp::ParameterValue(false)); node->get_parameter(plugin_name_ + ".angular_dist_threshold", angular_dist_threshold_); diff --git a/nav2_rotation_shim_controller/test/test_shim_controller.cpp b/nav2_rotation_shim_controller/test/test_shim_controller.cpp index 0645e5077b0..0b97876182f 100644 --- a/nav2_rotation_shim_controller/test/test_shim_controller.cpp +++ b/nav2_rotation_shim_controller/test/test_shim_controller.cpp @@ -21,7 +21,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_controller/plugins/simple_goal_checker.hpp" #include "nav2_rotation_shim_controller/nav2_rotation_shim_controller.hpp" #include "tf2_ros/transform_broadcaster.h" @@ -77,7 +77,7 @@ class RotationShimShim : public nav2_rotation_shim_controller::RotationShimContr TEST(RotationShimControllerTest, lifecycleTransitions) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto costmap = std::make_shared("fake_costmap"); @@ -115,7 +115,7 @@ TEST(RotationShimControllerTest, lifecycleTransitions) TEST(RotationShimControllerTest, setPlanAndSampledPointsTests) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto costmap = std::make_shared("fake_costmap"); @@ -165,7 +165,7 @@ TEST(RotationShimControllerTest, setPlanAndSampledPointsTests) TEST(RotationShimControllerTest, rotationAndTransformTests) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto costmap = std::make_shared("fake_costmap", "/", false); @@ -225,7 +225,7 @@ TEST(RotationShimControllerTest, rotationAndTransformTests) TEST(RotationShimControllerTest, computeVelocityTests) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto listener = std::make_shared(*tf, node, true); @@ -311,7 +311,7 @@ TEST(RotationShimControllerTest, computeVelocityTests) TEST(RotationShimControllerTest, openLoopRotationTests) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto listener = std::make_shared(*tf, node, true); @@ -389,7 +389,7 @@ TEST(RotationShimControllerTest, openLoopRotationTests) { TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto listener = std::make_shared(*tf, node, true); @@ -462,7 +462,7 @@ TEST(RotationShimControllerTest, computeVelocityGoalRotationTests) { TEST(RotationShimControllerTest, accelerationTests) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto listener = std::make_shared(*tf, node, true); @@ -541,7 +541,7 @@ TEST(RotationShimControllerTest, accelerationTests) { TEST(RotationShimControllerTest, isGoalChangedTest) { auto ctrl = std::make_shared(); - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); std::string name = "PathFollower"; auto tf = std::make_shared(node->get_clock()); auto listener = std::make_shared(*tf, node, true); @@ -591,7 +591,7 @@ TEST(RotationShimControllerTest, isGoalChangedTest) TEST(RotationShimControllerTest, testDynamicParameter) { - auto node = std::make_shared("ShimControllerTest"); + auto node = std::make_shared("ShimControllerTest"); auto costmap = std::make_shared("global_costmap"); std::string name = "test"; auto tf = std::make_shared(node->get_clock()); diff --git a/nav2_route/CMakeLists.txt b/nav2_route/CMakeLists.txt index db7825a0c96..47d29fbf87e 100644 --- a/nav2_route/CMakeLists.txt +++ b/nav2_route/CMakeLists.txt @@ -19,6 +19,7 @@ find_package(visualization_msgs REQUIRED) find_package(nav2_msgs REQUIRED) find_package(nanoflann REQUIRED) find_package(nlohmann_json REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -47,6 +48,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC nav2_core::nav2_core @@ -95,6 +97,7 @@ target_include_directories(edge_scorers PUBLIC "$" "$" + "$" ) target_link_libraries(edge_scorers PUBLIC nav2_core::nav2_core @@ -132,6 +135,7 @@ target_include_directories(route_operations PUBLIC "$" "$" + "$" ) target_link_libraries(route_operations PUBLIC nav2_core::nav2_core @@ -164,6 +168,7 @@ target_include_directories(graph_file_loaders PUBLIC "$" "$" + "$" ) target_link_libraries(graph_file_loaders PUBLIC nav2_core::nav2_core @@ -195,6 +200,7 @@ target_include_directories(graph_file_savers PUBLIC "$" "$" + "$" ) target_link_libraries(graph_file_savers PUBLIC nav2_core::nav2_core @@ -263,6 +269,7 @@ ament_export_dependencies( nav2_core nanoflann nlohmann_json + nav2_ros_common ) ament_export_libraries(${library_name} edge_scorers route_operations graph_file_loaders graph_file_savers) ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET) diff --git a/nav2_route/include/nav2_route/edge_scorer.hpp b/nav2_route/include/nav2_route/edge_scorer.hpp index 79653f92e3b..c294ac47e43 100644 --- a/nav2_route/include/nav2_route/edge_scorer.hpp +++ b/nav2_route/include/nav2_route/edge_scorer.hpp @@ -22,8 +22,8 @@ #include "tf2_ros/buffer.h" #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/types.hpp" #include "nav2_route/utils.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" @@ -49,7 +49,7 @@ class EdgeScorer * @brief Constructor */ explicit EdgeScorer( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, const std::shared_ptr costmap_subscriber); diff --git a/nav2_route/include/nav2_route/goal_intent_extractor.hpp b/nav2_route/include/nav2_route/goal_intent_extractor.hpp index 3072f2626c9..db26121fcef 100644 --- a/nav2_route/include/nav2_route/goal_intent_extractor.hpp +++ b/nav2_route/include/nav2_route/goal_intent_extractor.hpp @@ -22,7 +22,7 @@ #include "tf2_ros/transform_listener.h" #include "nav2_core/route_exceptions.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_msgs/action/compute_route.hpp" #include "nav2_msgs/action/compute_and_track_route.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" @@ -65,7 +65,7 @@ class GoalIntentExtractor * @param base_frame Robot reference frame */ void configure( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, Graph & graph, GraphToIDMap * id_to_graph_map, std::shared_ptr tf, diff --git a/nav2_route/include/nav2_route/goal_intent_search.hpp b/nav2_route/include/nav2_route/goal_intent_search.hpp index cd5a91d5476..237402c3ea4 100644 --- a/nav2_route/include/nav2_route/goal_intent_search.hpp +++ b/nav2_route/include/nav2_route/goal_intent_search.hpp @@ -32,6 +32,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/cost_values.hpp" #include "nav2_util/line_iterator.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_route { diff --git a/nav2_route/include/nav2_route/graph_loader.hpp b/nav2_route/include/nav2_route/graph_loader.hpp index ea602b11019..2a39da1bee1 100644 --- a/nav2_route/include/nav2_route/graph_loader.hpp +++ b/nav2_route/include/nav2_route/graph_loader.hpp @@ -22,10 +22,10 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_route/types.hpp" #include "nav2_route/interfaces/graph_file_loader.hpp" @@ -46,7 +46,7 @@ class GraphLoader * @param options Additional options to control creation of the node. */ explicit GraphLoader( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr tf, const std::string frame); diff --git a/nav2_route/include/nav2_route/graph_saver.hpp b/nav2_route/include/nav2_route/graph_saver.hpp index 328ec65840e..7cc25d83c04 100644 --- a/nav2_route/include/nav2_route/graph_saver.hpp +++ b/nav2_route/include/nav2_route/graph_saver.hpp @@ -22,10 +22,10 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/buffer.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_route/types.hpp" #include "nav2_route/interfaces/graph_file_saver.hpp" @@ -48,7 +48,7 @@ class GraphSaver * @param frame Coordinate frame that the graph belongs to */ explicit GraphSaver( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr tf, const std::string frame); diff --git a/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp b/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp index 7aa9a3123ee..e20bade1070 100644 --- a/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp +++ b/nav2_route/include/nav2_route/interfaces/edge_cost_function.hpp @@ -19,8 +19,7 @@ #include #include "tf2_ros/buffer.h" -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "nav2_route/types.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" @@ -56,7 +55,7 @@ class EdgeCostFunction * @param parent pointer to user's node */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) = 0; diff --git a/nav2_route/include/nav2_route/interfaces/graph_file_loader.hpp b/nav2_route/include/nav2_route/interfaces/graph_file_loader.hpp index 6774f0d1870..5c7682fca99 100644 --- a/nav2_route/include/nav2_route/interfaces/graph_file_loader.hpp +++ b/nav2_route/include/nav2_route/interfaces/graph_file_loader.hpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/types.hpp" namespace nav2_route @@ -50,7 +50,7 @@ class GraphFileLoader * @param parent pointer to user's node */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node) = 0; + const nav2::LifecycleNode::SharedPtr node) = 0; /** * @brief Method to load the graph from the filepath diff --git a/nav2_route/include/nav2_route/interfaces/graph_file_saver.hpp b/nav2_route/include/nav2_route/interfaces/graph_file_saver.hpp index 4851655e4dd..d64f18bf79d 100644 --- a/nav2_route/include/nav2_route/interfaces/graph_file_saver.hpp +++ b/nav2_route/include/nav2_route/interfaces/graph_file_saver.hpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/types.hpp" namespace nav2_route @@ -50,7 +50,7 @@ class GraphFileSaver * @param parent pointer to user's node */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node) = 0; + const nav2::LifecycleNode::SharedPtr node) = 0; /** * @brief Method to save the graph to the filepath diff --git a/nav2_route/include/nav2_route/interfaces/route_operation.hpp b/nav2_route/include/nav2_route/interfaces/route_operation.hpp index 0c5d140f3ad..4a5ba2affdc 100644 --- a/nav2_route/include/nav2_route/interfaces/route_operation.hpp +++ b/nav2_route/include/nav2_route/interfaces/route_operation.hpp @@ -19,8 +19,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "pluginlib/class_loader.hpp" #include "nav2_route/types.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" @@ -85,7 +84,7 @@ class RouteOperation * to correlate an operation instance to the navigation graph operation calls */ virtual void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber, const std::string & name) = 0; diff --git a/nav2_route/include/nav2_route/node_spatial_tree.hpp b/nav2_route/include/nav2_route/node_spatial_tree.hpp index ac5347bc0bd..15d9e2a5528 100644 --- a/nav2_route/include/nav2_route/node_spatial_tree.hpp +++ b/nav2_route/include/nav2_route/node_spatial_tree.hpp @@ -20,7 +20,7 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/types.hpp" #include "nav2_route/utils.hpp" diff --git a/nav2_route/include/nav2_route/operations_manager.hpp b/nav2_route/include/nav2_route/operations_manager.hpp index b30045f94c9..11f6edda21a 100644 --- a/nav2_route/include/nav2_route/operations_manager.hpp +++ b/nav2_route/include/nav2_route/operations_manager.hpp @@ -19,9 +19,9 @@ #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_core/route_exceptions.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/types.hpp" #include "nav2_route/utils.hpp" #include "nav2_route/interfaces/route_operation.hpp" @@ -45,7 +45,7 @@ class OperationsManager * @brief A constructor for nav2_route::OperationsManager */ explicit OperationsManager( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber); /** diff --git a/nav2_route/include/nav2_route/path_converter.hpp b/nav2_route/include/nav2_route/path_converter.hpp index c4454f768ba..27f244ecc65 100644 --- a/nav2_route/include/nav2_route/path_converter.hpp +++ b/nav2_route/include/nav2_route/path_converter.hpp @@ -22,8 +22,8 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_route/types.hpp" #include "nav2_route/utils.hpp" #include "nav2_route/corner_smoothing.hpp" @@ -51,7 +51,7 @@ class PathConverter * @brief Configure the object * @param node Node to use to get params and create interfaces */ - void configure(nav2_util::LifecycleNode::SharedPtr node); + void configure(nav2::LifecycleNode::SharedPtr node); /** * @brief Convert a Route into a dense path @@ -80,7 +80,7 @@ class PathConverter std::vector & poses); protected: - rclcpp_lifecycle::LifecyclePublisher::SharedPtr path_pub_; + nav2::Publisher::SharedPtr path_pub_; rclcpp::Logger logger_{rclcpp::get_logger("PathConverter")}; float density_; float smoothing_radius_; diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/costmap_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/costmap_scorer.hpp index dfa632962a7..74375187cda 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/costmap_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/costmap_scorer.hpp @@ -18,11 +18,10 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" #include "nav2_util/line_iterator.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" namespace nav2_route @@ -50,7 +49,7 @@ class CostmapScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/distance_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/distance_scorer.hpp index 6e57c9a78c3..f9e13560f05 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/distance_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/distance_scorer.hpp @@ -18,10 +18,9 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_route { @@ -48,7 +47,7 @@ class DistanceScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/dynamic_edges_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/dynamic_edges_scorer.hpp index e28c484600f..ff4a10a18b5 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/dynamic_edges_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/dynamic_edges_scorer.hpp @@ -20,11 +20,11 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" #include "nav2_msgs/srv/dynamic_edges.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/service_server.hpp" namespace nav2_route { @@ -51,7 +51,7 @@ class DynamicEdgesScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; @@ -79,6 +79,7 @@ class DynamicEdgesScorer : public EdgeCostFunction * @param response Response to service (empty) */ void closedEdgesCb( + const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response); @@ -87,7 +88,7 @@ class DynamicEdgesScorer : public EdgeCostFunction std::string name_; std::set closed_edges_; std::unordered_map dynamic_penalties_; - rclcpp::Service::SharedPtr service_; + nav2::ServiceServer::SharedPtr service_; }; } // namespace nav2_route diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp index a2886347f8b..d01d74c8c71 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/goal_orientation_scorer.hpp @@ -18,12 +18,11 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/route_exceptions.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" #include "nav2_util/line_iterator.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/utils.hpp" @@ -57,7 +56,7 @@ class GoalOrientationScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/penalty_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/penalty_scorer.hpp index 476fe2f269b..959e5596a69 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/penalty_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/penalty_scorer.hpp @@ -18,10 +18,9 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_route { @@ -47,7 +46,7 @@ class PenaltyScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/semantic_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/semantic_scorer.hpp index eabeb980478..f3fee0d5701 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/semantic_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/semantic_scorer.hpp @@ -19,10 +19,9 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_route { @@ -49,7 +48,7 @@ class SemanticScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/start_pose_orientation_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/start_pose_orientation_scorer.hpp index a0b2e132d02..3a755a8de98 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/start_pose_orientation_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/start_pose_orientation_scorer.hpp @@ -18,12 +18,11 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/route_exceptions.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" #include "nav2_util/line_iterator.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" @@ -58,7 +57,7 @@ class StartPoseOrientationScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/edge_cost_functions/time_scorer.hpp b/nav2_route/include/nav2_route/plugins/edge_cost_functions/time_scorer.hpp index 1213a7d9391..03be56e9057 100644 --- a/nav2_route/include/nav2_route/plugins/edge_cost_functions/time_scorer.hpp +++ b/nav2_route/include/nav2_route/plugins/edge_cost_functions/time_scorer.hpp @@ -18,10 +18,9 @@ #include #include -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/interfaces/edge_cost_function.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_route { @@ -49,7 +48,7 @@ class TimeScorer : public EdgeCostFunction * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp b/nav2_route/include/nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp index 0cb9f34ae17..f900aeee1af 100644 --- a/nav2_route/include/nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp +++ b/nav2_route/include/nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp @@ -19,6 +19,7 @@ #include "nav2_core/route_exceptions.hpp" #include "nav2_route/interfaces/graph_file_loader.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #ifndef NAV2_ROUTE__PLUGINS__GRAPH_FILE_LOADERS__GEOJSON_GRAPH_FILE_LOADER_HPP_ #define NAV2_ROUTE__PLUGINS__GRAPH_FILE_LOADERS__GEOJSON_GRAPH_FILE_LOADER_HPP_ @@ -50,7 +51,7 @@ class GeoJsonGraphFileLoader : public GraphFileLoader * @param parent pointer to user's node */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node) override; + const nav2::LifecycleNode::SharedPtr node) override; /** * @brief Loads the geojson file into the graph diff --git a/nav2_route/include/nav2_route/plugins/graph_file_savers/geojson_graph_file_saver.hpp b/nav2_route/include/nav2_route/plugins/graph_file_savers/geojson_graph_file_saver.hpp index 6352462c8da..7f95a88c9ca 100644 --- a/nav2_route/include/nav2_route/plugins/graph_file_savers/geojson_graph_file_saver.hpp +++ b/nav2_route/include/nav2_route/plugins/graph_file_savers/geojson_graph_file_saver.hpp @@ -20,6 +20,7 @@ #include "nav2_core/route_exceptions.hpp" #include "nav2_route/interfaces/graph_file_saver.hpp" #include "nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #ifndef NAV2_ROUTE__PLUGINS__GRAPH_FILE_SAVERS__GEOJSON_GRAPH_FILE_SAVER_HPP_ #define NAV2_ROUTE__PLUGINS__GRAPH_FILE_SAVERS__GEOJSON_GRAPH_FILE_SAVER_HPP_ @@ -51,7 +52,7 @@ class GeoJsonGraphFileSaver : public GraphFileSaver * @param parent pointer to user's node */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node) override; + const nav2::LifecycleNode::SharedPtr node) override; /** * @brief Saves the graph to a geojson file diff --git a/nav2_route/include/nav2_route/plugins/route_operation_client.hpp b/nav2_route/include/nav2_route/plugins/route_operation_client.hpp index e0862ed81e2..1dc94404e88 100644 --- a/nav2_route/include/nav2_route/plugins/route_operation_client.hpp +++ b/nav2_route/include/nav2_route/plugins/route_operation_client.hpp @@ -23,7 +23,8 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "nav2_route/interfaces/route_operation.hpp" #include "nav2_core/route_exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/service_client.hpp" #include "std_srvs/srv/trigger.hpp" namespace nav2_route @@ -77,7 +78,7 @@ class RouteOperationClient : public RouteOperation * main service name and existence. */ virtual void configureEvent( - const rclcpp_lifecycle::LifecycleNode::SharedPtr /*node*/, + const nav2::LifecycleNode::SharedPtr /*node*/, const std::string & /*name*/) {} /** @@ -97,7 +98,7 @@ class RouteOperationClient : public RouteOperation * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr, const std::string & name) final { @@ -105,12 +106,8 @@ class RouteOperationClient : public RouteOperation name_ = name; logger_ = node->get_logger(); node_ = node; - callback_group_ = node->create_callback_group( - rclcpp::CallbackGroupType::MutuallyExclusive, - false); - callback_group_executor_.add_callback_group(callback_group_, node->get_node_base_interface()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".service_name", rclcpp::ParameterValue("")); main_srv_name_ = node->get_parameter(getName() + ".service_name").as_string(); @@ -120,8 +117,8 @@ class RouteOperationClient : public RouteOperation // If this is set to empty string after configuration, then the individual nodes will // indicate the endpoint for the particular service call. if (!main_srv_name_.empty()) { - main_client_ = node->create_client( - main_srv_name_, rclcpp::SystemDefaultsQoS(), callback_group_); + main_client_ = + node->create_client(main_srv_name_, true); } } @@ -156,14 +153,24 @@ class RouteOperationClient : public RouteOperation "set in the param file or in the operation's metadata!"); } - if (srv_name.empty()) { - srv_name = main_srv_name_; - response = callService(main_client_, req); - } else { - auto node = node_.lock(); - auto client = node->create_client( - srv_name, rclcpp::SystemDefaultsQoS(), callback_group_); - response = callService(client, req); + try { + if (srv_name.empty()) { + srv_name = main_srv_name_; + response = main_client_->invoke(req, std::chrono::nanoseconds(500ms)); + } else { + auto node = node_.lock(); + if (!node) { + throw nav2_core::OperationFailed( + "Route operation service (" + getName() + ") failed to lock node."); + } + auto client = + node->create_client(srv_name, true); + response = client->invoke(req, std::chrono::nanoseconds(500ms)); + } + } catch (const std::exception & e) { + throw nav2_core::OperationFailed( + "Route operation service (" + getName() + ") failed to call service: " + + srv_name + " at Node " + std::to_string(node_achieved->nodeid)); } RCLCPP_INFO( @@ -173,30 +180,6 @@ class RouteOperationClient : public RouteOperation return processResponse(response); } - std::shared_ptr callService( - typename rclcpp::Client::SharedPtr client, - std::shared_ptr req, - const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(500ms)) - { - auto node = node_.lock(); - if (!client->wait_for_service(1s)) { - throw nav2_core::OperationFailed( - "Route operation service " + - std::string(client->get_service_name()) + " is not available!"); - } - - auto result = client->async_send_request(req); - if (callback_group_executor_.spin_until_future_complete(result, timeout) != - rclcpp::FutureReturnCode::SUCCESS) - { - throw nav2_core::OperationFailed( - "Route operation service " + - std::string(client->get_service_name()) + " failed to call!"); - } - - return result.get(); - } - /** * @brief Get name of the plugin for parameter scope mapping * @return Name @@ -213,10 +196,8 @@ class RouteOperationClient : public RouteOperation std::string name_, main_srv_name_; std::atomic_bool reroute_; rclcpp::Logger logger_{rclcpp::get_logger("RouteOperationClient")}; - typename rclcpp::Client::SharedPtr main_client_; - rclcpp_lifecycle::LifecycleNode::WeakPtr node_; - rclcpp::CallbackGroup::SharedPtr callback_group_; - rclcpp::executors::SingleThreadedExecutor callback_group_executor_; + typename nav2::ServiceClient::SharedPtr main_client_; + nav2::LifecycleNode::WeakPtr node_; }; } // namespace nav2_route diff --git a/nav2_route/include/nav2_route/plugins/route_operations/adjust_speed_limit.hpp b/nav2_route/include/nav2_route/plugins/route_operations/adjust_speed_limit.hpp index 899e0837094..a9c2639f2df 100644 --- a/nav2_route/include/nav2_route/plugins/route_operations/adjust_speed_limit.hpp +++ b/nav2_route/include/nav2_route/plugins/route_operations/adjust_speed_limit.hpp @@ -21,7 +21,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "nav2_route/interfaces/route_operation.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_msgs/msg/speed_limit.hpp" namespace nav2_route @@ -49,7 +49,7 @@ class AdjustSpeedLimit : public RouteOperation * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber, const std::string & name) override; @@ -89,7 +89,7 @@ class AdjustSpeedLimit : public RouteOperation std::string name_; std::string speed_tag_; rclcpp::Logger logger_{rclcpp::get_logger("AdjustSpeedLimit")}; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr speed_limit_pub_; + nav2::Publisher::SharedPtr speed_limit_pub_; }; } // namespace nav2_route diff --git a/nav2_route/include/nav2_route/plugins/route_operations/collision_monitor.hpp b/nav2_route/include/nav2_route/plugins/route_operations/collision_monitor.hpp index 9c73ef8f395..0b392e49969 100644 --- a/nav2_route/include/nav2_route/plugins/route_operations/collision_monitor.hpp +++ b/nav2_route/include/nav2_route/plugins/route_operations/collision_monitor.hpp @@ -25,7 +25,7 @@ #include "nav2_route/utils.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_util/line_iterator.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_core/route_exceptions.hpp" namespace nav2_route @@ -62,7 +62,7 @@ class CollisionMonitor : public RouteOperation * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/route_operations/rerouting_service.hpp b/nav2_route/include/nav2_route/plugins/route_operations/rerouting_service.hpp index 30e6e97353b..e9c56ad1975 100644 --- a/nav2_route/include/nav2_route/plugins/route_operations/rerouting_service.hpp +++ b/nav2_route/include/nav2_route/plugins/route_operations/rerouting_service.hpp @@ -21,8 +21,9 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "nav2_route/interfaces/route_operation.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "std_srvs/srv/trigger.hpp" +#include "nav2_ros_common/service_server.hpp" namespace nav2_route { @@ -48,7 +49,7 @@ class ReroutingService : public RouteOperation * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber, const std::string & name) override; @@ -90,6 +91,7 @@ class ReroutingService : public RouteOperation * @param response, returns success */ void serviceCb( + const std::shared_ptr request_header, const std::shared_ptr request, std::shared_ptr response); @@ -97,7 +99,7 @@ class ReroutingService : public RouteOperation std::string name_; std::atomic_bool reroute_; rclcpp::Logger logger_{rclcpp::get_logger("ReroutingService")}; - rclcpp::Service::SharedPtr service_; + typename nav2::ServiceServer::SharedPtr service_; }; } // namespace nav2_route diff --git a/nav2_route/include/nav2_route/plugins/route_operations/time_marker.hpp b/nav2_route/include/nav2_route/plugins/route_operations/time_marker.hpp index 584c5d49c9c..0d3208cc5eb 100644 --- a/nav2_route/include/nav2_route/plugins/route_operations/time_marker.hpp +++ b/nav2_route/include/nav2_route/plugins/route_operations/time_marker.hpp @@ -21,7 +21,7 @@ #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "nav2_route/interfaces/route_operation.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_msgs/msg/speed_limit.hpp" namespace nav2_route @@ -49,7 +49,7 @@ class TimeMarker : public RouteOperation * @brief Configure */ void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber, const std::string & name) override; diff --git a/nav2_route/include/nav2_route/plugins/route_operations/trigger_event.hpp b/nav2_route/include/nav2_route/plugins/route_operations/trigger_event.hpp index 39e77532392..9c6b8d795d8 100644 --- a/nav2_route/include/nav2_route/plugins/route_operations/trigger_event.hpp +++ b/nav2_route/include/nav2_route/plugins/route_operations/trigger_event.hpp @@ -23,7 +23,7 @@ #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "nav2_route/interfaces/route_operation.hpp" #include "nav2_core/route_exceptions.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "std_srvs/srv/trigger.hpp" #include "nav2_route/plugins/route_operation_client.hpp" diff --git a/nav2_route/include/nav2_route/route_planner.hpp b/nav2_route/include/nav2_route/route_planner.hpp index 3a75c70bf34..bdadc6c9dd0 100644 --- a/nav2_route/include/nav2_route/route_planner.hpp +++ b/nav2_route/include/nav2_route/route_planner.hpp @@ -29,6 +29,7 @@ #include "nav2_route/edge_scorer.hpp" #include "nav2_core/route_exceptions.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_route { @@ -56,7 +57,7 @@ class RoutePlanner * @param costmap_subscriber Costmap subscriber to use for blocked nodes */ void configure( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, const std::shared_ptr costmap_subscriber); diff --git a/nav2_route/include/nav2_route/route_server.hpp b/nav2_route/include/nav2_route/route_server.hpp index a6b830c1b0e..3d384e93c0b 100644 --- a/nav2_route/include/nav2_route/route_server.hpp +++ b/nav2_route/include/nav2_route/route_server.hpp @@ -22,13 +22,13 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "tf2_ros/transform_listener.h" #include "tf2_ros/create_timer_ros.h" -#include "nav2_util/simple_action_server.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/simple_action_server.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/service_server.hpp" +#include "nav2_ros_common/service_server.hpp" #include "nav2_msgs/action/compute_route.hpp" #include "nav2_msgs/action/compute_and_track_route.hpp" #include "nav2_msgs/msg/route.hpp" @@ -52,19 +52,19 @@ namespace nav2_route * @brief An action server implements a Navigation Route-Graph planner * to compliment free-space planning in the Planner Server */ -class RouteServer : public nav2_util::LifecycleNode +class RouteServer : public nav2::LifecycleNode { public: using ComputeRoute = nav2_msgs::action::ComputeRoute; using ComputeRouteGoal = ComputeRoute::Goal; using ComputeRouteResult = ComputeRoute::Result; - using ComputeRouteServer = nav2_util::SimpleActionServer; + using ComputeRouteServer = nav2::SimpleActionServer; using ComputeAndTrackRoute = nav2_msgs::action::ComputeAndTrackRoute; using ComputeAndTrackRouteGoal = ComputeAndTrackRoute::Goal; using ComputeAndTrackRouteFeedback = ComputeAndTrackRoute::Feedback; using ComputeAndTrackRouteResult = ComputeAndTrackRoute::Result; - using ComputeAndTrackRouteServer = nav2_util::SimpleActionServer; + using ComputeAndTrackRouteServer = nav2::SimpleActionServer; /** * @brief A constructor for nav2_route::RouteServer @@ -82,35 +82,35 @@ class RouteServer : public nav2_util::LifecycleNode * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activate member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivate member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Reset member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in shutdown state * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** * @brief Main route action server callbacks for computing and tracking a route @@ -138,7 +138,7 @@ class RouteServer : public nav2_util::LifecycleNode */ template void processRouteRequest( - std::shared_ptr> & action_server); + typename nav2::SimpleActionServer::SharedPtr & action_server); /** * @brief Find the planning duration of the request and log warnings @@ -153,7 +153,7 @@ class RouteServer : public nav2_util::LifecycleNode * @return if the request is valid */ template - bool isRequestValid(std::shared_ptr> & action_server); + bool isRequestValid(typename nav2::SimpleActionServer::SharedPtr & action_server); /** * @brief Populate result for compute route action @@ -200,20 +200,19 @@ class RouteServer : public nav2_util::LifecycleNode template void exceptionWarning(const std::shared_ptr goal, const std::exception & ex); - std::shared_ptr compute_route_server_; - std::shared_ptr compute_and_track_route_server_; + typename ComputeRouteServer::SharedPtr compute_route_server_; + typename ComputeAndTrackRouteServer::SharedPtr compute_and_track_route_server_; // TF std::shared_ptr tf_; std::shared_ptr transform_listener_; // Publish the route for visualization - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr graph_vis_publisher_; // Set or modify graph - nav2_util::ServiceServer>::SharedPtr set_graph_service_; + nav2::ServiceServer::SharedPtr set_graph_service_; // Internal tools std::shared_ptr graph_loader_; diff --git a/nav2_route/include/nav2_route/route_tracker.hpp b/nav2_route/include/nav2_route/route_tracker.hpp index d4ccb66a51e..9c2e7058aec 100644 --- a/nav2_route/include/nav2_route/route_tracker.hpp +++ b/nav2_route/include/nav2_route/route_tracker.hpp @@ -18,7 +18,7 @@ #include "tf2_ros/transform_listener.h" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/simple_action_server.hpp" #include "nav2_msgs/action/compute_and_track_route.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_core/route_exceptions.hpp" @@ -38,7 +38,7 @@ namespace nav2_route class RouteTracker { public: - using ActionServerTrack = nav2_util::SimpleActionServer; + using ActionServerTrack = nav2::SimpleActionServer; using Feedback = nav2_msgs::action::ComputeAndTrackRoute::Feedback; /** @@ -57,10 +57,10 @@ class RouteTracker * @param route_frame Frame of route navigation */ void configure( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, - std::shared_ptr action_server, + typename ActionServerTrack::SharedPtr action_server, const std::string & route_frame, const std::string & base_frame); @@ -124,7 +124,7 @@ class RouteTracker rclcpp::Logger logger_{rclcpp::get_logger("RouteTracker")}; double radius_threshold_, boundary_radius_threshold_, tracker_update_rate_; bool aggregate_blocked_ids_; - std::shared_ptr action_server_; + typename ActionServerTrack::SharedPtr action_server_; std::unique_ptr operations_manager_; std::shared_ptr tf_buffer_; }; diff --git a/nav2_route/package.xml b/nav2_route/package.xml index d33cb7e942b..855356eefc2 100644 --- a/nav2_route/package.xml +++ b/nav2_route/package.xml @@ -25,6 +25,7 @@ angles libnanoflann-dev nlohmann-json-dev + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_route/src/edge_scorer.cpp b/nav2_route/src/edge_scorer.cpp index d98ddf46973..1bfd3830ed8 100644 --- a/nav2_route/src/edge_scorer.cpp +++ b/nav2_route/src/edge_scorer.cpp @@ -23,7 +23,7 @@ namespace nav2_route { EdgeScorer::EdgeScorer( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, const std::shared_ptr costmap_subscriber) : plugin_loader_("nav2_route", "nav2_route::EdgeCostFunction") @@ -33,20 +33,20 @@ EdgeScorer::EdgeScorer( const std::vector default_plugin_types( {"nav2_route::DistanceScorer", "nav2_route::DynamicEdgesScorer"}); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "edge_cost_functions", rclcpp::ParameterValue(default_plugin_ids)); auto edge_cost_function_ids = node->get_parameter("edge_cost_functions").as_string_array(); if (edge_cost_function_ids == default_plugin_ids) { for (unsigned int i = 0; i != edge_cost_function_ids.size(); i++) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_plugin_ids[i] + ".plugin", rclcpp::ParameterValue(default_plugin_types[i])); } } for (size_t i = 0; i != edge_cost_function_ids.size(); i++) { try { - std::string type = nav2_util::get_plugin_type_param( + std::string type = nav2::get_plugin_type_param( node, edge_cost_function_ids[i]); EdgeCostFunction::Ptr scorer = plugin_loader_.createUniqueInstance(type); RCLCPP_INFO( diff --git a/nav2_route/src/goal_intent_extractor.cpp b/nav2_route/src/goal_intent_extractor.cpp index 210e8911975..14443b77641 100644 --- a/nav2_route/src/goal_intent_extractor.cpp +++ b/nav2_route/src/goal_intent_extractor.cpp @@ -24,7 +24,7 @@ namespace nav2_route static float EPSILON = 1e-6; void GoalIntentExtractor::configure( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, Graph & graph, GraphToIDMap * id_to_graph_map, std::shared_ptr tf, @@ -42,31 +42,31 @@ void GoalIntentExtractor::configure( node_spatial_tree_ = std::make_shared(); node_spatial_tree_->computeTree(graph); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "prune_goal", rclcpp::ParameterValue(true)); prune_goal_ = node->get_parameter("prune_goal").as_bool(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "max_prune_dist_from_edge", rclcpp::ParameterValue(8.0)); max_dist_from_edge_ = static_cast( node->get_parameter("max_prune_dist_from_edge").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "min_prune_dist_from_goal", rclcpp::ParameterValue(0.15)); min_dist_from_goal_ = static_cast( node->get_parameter("min_prune_dist_from_goal").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "min_prune_dist_from_start", rclcpp::ParameterValue(0.10)); min_dist_from_start_ = static_cast( node->get_parameter("min_prune_dist_from_start").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "enable_nn_search", rclcpp::ParameterValue(true)); enable_search_ = node->get_parameter("enable_nn_search").as_bool(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "max_nn_search_iterations", rclcpp::ParameterValue(10000)); max_nn_search_iterations_ = node->get_parameter("max_nn_search_iterations").as_int(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "num_nearest_nodes", rclcpp::ParameterValue(5)); int num_of_nearest_nodes = node->get_parameter("num_nearest_nodes").as_int(); node_spatial_tree_->setNumOfNearestNodes(num_of_nearest_nodes); diff --git a/nav2_route/src/graph_loader.cpp b/nav2_route/src/graph_loader.cpp index 268c04760af..1c71012e866 100644 --- a/nav2_route/src/graph_loader.cpp +++ b/nav2_route/src/graph_loader.cpp @@ -21,7 +21,7 @@ namespace nav2_route { GraphLoader::GraphLoader( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr tf, const std::string frame) : plugin_loader_("nav2_route", "nav2_route::GraphFileLoader"), @@ -31,23 +31,23 @@ GraphLoader::GraphLoader( tf_ = tf; route_frame_ = frame; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue(std::string(""))); graph_filepath_ = node->get_parameter("graph_filepath").as_string(); // Default Graph Parser - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_file_loader", rclcpp::ParameterValue(default_plugin_id_)); auto graph_file_loader_id = node->get_parameter("graph_file_loader").as_string(); if (graph_file_loader_id == default_plugin_id_) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_plugin_id_ + ".plugin", rclcpp::ParameterValue("nav2_route::GeoJsonGraphFileLoader")); } // Create graph file loader plugin try { - plugin_type_ = nav2_util::get_plugin_type_param(node, graph_file_loader_id); + plugin_type_ = nav2::get_plugin_type_param(node, graph_file_loader_id); graph_file_loader_ = plugin_loader_.createSharedInstance((plugin_type_)); RCLCPP_INFO( logger_, "Created GraphFileLoader %s of type %s", diff --git a/nav2_route/src/graph_saver.cpp b/nav2_route/src/graph_saver.cpp index be0386ce883..664d51fd8ae 100644 --- a/nav2_route/src/graph_saver.cpp +++ b/nav2_route/src/graph_saver.cpp @@ -21,7 +21,7 @@ namespace nav2_route { GraphSaver::GraphSaver( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr tf, const std::string frame) : plugin_loader_("nav2_route", "nav2_route::GraphFileSaver"), @@ -31,23 +31,23 @@ GraphSaver::GraphSaver( tf_ = tf; route_frame_ = frame; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue(std::string(""))); graph_filepath_ = node->get_parameter("graph_filepath").as_string(); // Default Graph Parser const std::string default_plugin_type = "nav2_route::GeoJsonGraphFileSaver"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_file_saver", rclcpp::ParameterValue(default_plugin_id_)); auto graph_file_saver_id = node->get_parameter("graph_file_saver").as_string(); if (graph_file_saver_id == default_plugin_id_) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_plugin_id_ + ".plugin", rclcpp::ParameterValue(default_plugin_type)); } // Create graph file saver plugin try { - plugin_type_ = nav2_util::get_plugin_type_param(node, graph_file_saver_id); + plugin_type_ = nav2::get_plugin_type_param(node, graph_file_saver_id); graph_file_saver_ = plugin_loader_.createSharedInstance((plugin_type_)); RCLCPP_INFO( logger_, "Created GraphFileSaver %s of type %s", diff --git a/nav2_route/src/operations_manager.cpp b/nav2_route/src/operations_manager.cpp index ce883de929e..eba58a7f029 100644 --- a/nav2_route/src/operations_manager.cpp +++ b/nav2_route/src/operations_manager.cpp @@ -14,8 +14,8 @@ #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/types.hpp" #include "nav2_route/utils.hpp" #include "nav2_route/interfaces/route_operation.hpp" @@ -25,7 +25,7 @@ namespace nav2_route { OperationsManager::OperationsManager( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber) : plugin_loader_("nav2_route", "nav2_route::RouteOperation") { @@ -37,13 +37,13 @@ OperationsManager::OperationsManager( const std::vector default_plugin_types( {"nav2_route::AdjustSpeedLimit", "nav2_route::ReroutingService"}); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "operations", rclcpp::ParameterValue(default_plugin_ids)); auto operation_ids = node->get_parameter("operations").as_string_array(); if (operation_ids == default_plugin_ids) { for (unsigned int i = 0; i != operation_ids.size(); i++) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_plugin_ids[i] + ".plugin", rclcpp::ParameterValue(default_plugin_types[i])); } } @@ -51,7 +51,7 @@ OperationsManager::OperationsManager( // Create plugins and sort them into On Query, Status Change, and Graph-calling Operations for (size_t i = 0; i != operation_ids.size(); i++) { try { - std::string type = nav2_util::get_plugin_type_param(node, operation_ids[i]); + std::string type = nav2::get_plugin_type_param(node, operation_ids[i]); RouteOperation::Ptr operation = plugin_loader_.createSharedInstance(type); RCLCPP_INFO( node->get_logger(), "Created route operation %s of type %s", diff --git a/nav2_route/src/path_converter.cpp b/nav2_route/src/path_converter.cpp index 85607a5491b..ff48773dcea 100644 --- a/nav2_route/src/path_converter.cpp +++ b/nav2_route/src/path_converter.cpp @@ -24,20 +24,20 @@ namespace nav2_route { -void PathConverter::configure(nav2_util::LifecycleNode::SharedPtr node) +void PathConverter::configure(nav2::LifecycleNode::SharedPtr node) { // Density to make path points - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "path_density", rclcpp::ParameterValue(0.05)); density_ = static_cast(node->get_parameter("path_density").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "smoothing_radius", rclcpp::ParameterValue(1.0)); smoothing_radius_ = static_cast(node->get_parameter("smoothing_radius").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "smooth_corners", rclcpp::ParameterValue(false)); smooth_corners_ = node->get_parameter("smooth_corners").as_bool(); - path_pub_ = node->create_publisher("plan", 1); + path_pub_ = node->create_publisher("plan"); path_pub_->on_activate(); logger_ = node->get_logger(); } diff --git a/nav2_route/src/plugins/edge_cost_functions/costmap_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/costmap_scorer.cpp index 445f2572328..1af089a0384 100644 --- a/nav2_route/src/plugins/edge_cost_functions/costmap_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/costmap_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void CostmapScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr/* tf_buffer */, std::shared_ptr costmap_subscriber, const std::string & name) @@ -32,36 +32,36 @@ void CostmapScorer::configure( clock_ = node->get_clock(); // Find whether to use average or maximum cost values - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".use_maximum", rclcpp::ParameterValue(true)); use_max_ = static_cast(node->get_parameter(getName() + ".use_maximum").as_bool()); // Edge is invalid if its in collision - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".invalid_on_collision", rclcpp::ParameterValue(true)); invalid_on_collision_ = static_cast(node->get_parameter(getName() + ".invalid_on_collision").as_bool()); // Edge is invalid if edge is off the costmap - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".invalid_off_map", rclcpp::ParameterValue(true)); invalid_off_map_ = static_cast(node->get_parameter(getName() + ".invalid_off_map").as_bool()); // Max cost to be considered valid - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".max_cost", rclcpp::ParameterValue(253.0)); max_cost_ = static_cast(node->get_parameter(getName() + ".max_cost").as_double()); // Resolution to check the costmap over (1=every cell, 2=every other cell, etc.) - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".check_resolution", rclcpp::ParameterValue(2)); check_resolution_ = static_cast( node->get_parameter(getName() + ".check_resolution").as_int()); // Create costmap subscriber if not the same as the server costmap std::string server_costmap_topic = node->get_parameter("costmap_topic").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".costmap_topic", rclcpp::ParameterValue(std::string("global_costmap/costmap_raw"))); std::string costmap_topic = @@ -77,7 +77,7 @@ void CostmapScorer::configure( } // Find the proportional weight to apply, if multiple cost functions - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".weight", rclcpp::ParameterValue(1.0)); weight_ = static_cast(node->get_parameter(getName() + ".weight").as_double()); } diff --git a/nav2_route/src/plugins/edge_cost_functions/distance_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/distance_scorer.cpp index 28e313db8cb..91d9fd8f7a9 100644 --- a/nav2_route/src/plugins/edge_cost_functions/distance_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/distance_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void DistanceScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr/* tf_buffer */, std::shared_ptr/* costmap_subscriber */, const std::string & name) @@ -30,12 +30,12 @@ void DistanceScorer::configure( name_ = name; // Find the tag at high the speed limit information is stored - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".speed_tag", rclcpp::ParameterValue("speed_limit")); speed_tag_ = node->get_parameter(getName() + ".speed_tag").as_string(); // Find the proportional weight to apply, if multiple cost functions - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".weight", rclcpp::ParameterValue(1.0)); weight_ = static_cast(node->get_parameter(getName() + ".weight").as_double()); } diff --git a/nav2_route/src/plugins/edge_cost_functions/dynamic_edges_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/dynamic_edges_scorer.cpp index bd0a9a3c4ba..af6ca2f2e72 100644 --- a/nav2_route/src/plugins/edge_cost_functions/dynamic_edges_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/dynamic_edges_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void DynamicEdgesScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr/* tf_buffer */, std::shared_ptr/* costmap_subscriber */, const std::string & name) @@ -31,15 +31,16 @@ void DynamicEdgesScorer::configure( logger_ = node->get_logger(); service_ = node->create_service( - std::string(node->get_name()) + "/" + getName() + "/adjust_edges", std::bind( - &DynamicEdgesScorer::closedEdgesCb, this, - std::placeholders::_1, std::placeholders::_2)); + std::string(node->get_name()) + "/" + getName() + "/adjust_edges", + std::bind(&DynamicEdgesScorer::closedEdgesCb, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); dynamic_penalties_.clear(); closed_edges_.clear(); } void DynamicEdgesScorer::closedEdgesCb( + const std::shared_ptr, const std::shared_ptr request, std::shared_ptr response) { diff --git a/nav2_route/src/plugins/edge_cost_functions/goal_orientation_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/goal_orientation_scorer.cpp index cfd0d82f0c0..a4c08c542bd 100644 --- a/nav2_route/src/plugins/edge_cost_functions/goal_orientation_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/goal_orientation_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void GoalOrientationScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr/* tf_buffer */, std::shared_ptr/* costmap_subscriber */, const std::string & name) @@ -30,13 +30,13 @@ void GoalOrientationScorer::configure( name_ = name; logger_ = node->get_logger(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".orientation_tolerance", rclcpp::ParameterValue(M_PI / 2.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".orientation_weight", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".use_orientation_threshold", rclcpp::ParameterValue(false)); orientation_tolerance_ = node->get_parameter(getName() + ".orientation_tolerance").as_double(); diff --git a/nav2_route/src/plugins/edge_cost_functions/penalty_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/penalty_scorer.cpp index 409054fff75..661d4fb52d4 100644 --- a/nav2_route/src/plugins/edge_cost_functions/penalty_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/penalty_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void PenaltyScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr/* tf_buffer */, std::shared_ptr/* costmap_subscriber */, const std::string & name) @@ -30,12 +30,12 @@ void PenaltyScorer::configure( name_ = name; // Find the tag at high the speed limit information is stored - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".penalty_tag", rclcpp::ParameterValue("penalty")); penalty_tag_ = node->get_parameter(getName() + ".penalty_tag").as_string(); // Find the proportional weight to apply, if multiple cost functions - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".weight", rclcpp::ParameterValue(1.0)); weight_ = static_cast(node->get_parameter(getName() + ".weight").as_double()); } diff --git a/nav2_route/src/plugins/edge_cost_functions/semantic_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/semantic_scorer.cpp index f44fbf18f47..37d06d8c759 100644 --- a/nav2_route/src/plugins/edge_cost_functions/semantic_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/semantic_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void SemanticScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr/* tf_buffer */, std::shared_ptr/* costmap_subscriber */, const std::string & name) @@ -30,12 +30,12 @@ void SemanticScorer::configure( name_ = name; // Find the semantic data - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".semantic_classes", rclcpp::ParameterValue(std::vector{})); std::vector classes = node->get_parameter(getName() + ".semantic_classes").as_string_array(); for (auto & cl : classes) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + "." + cl, rclcpp::ParameterType::PARAMETER_DOUBLE); const double cost = node->get_parameter(getName() + "." + cl).as_double(); semantic_info_[cl] = static_cast(cost); @@ -43,12 +43,12 @@ void SemanticScorer::configure( // Find the key to look for semantic data for within the metadata. If set to empty string, // will search instead for any key in the metadata. - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".semantic_key", rclcpp::ParameterValue(std::string("class"))); key_ = node->get_parameter(getName() + ".semantic_key").as_string(); // Find the proportional weight to apply, if multiple cost functions - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".weight", rclcpp::ParameterValue(1.0)); weight_ = static_cast(node->get_parameter(getName() + ".weight").as_double()); } diff --git a/nav2_route/src/plugins/edge_cost_functions/start_pose_orientation_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/start_pose_orientation_scorer.cpp index 13fd5762a3e..b523ec9a585 100644 --- a/nav2_route/src/plugins/edge_cost_functions/start_pose_orientation_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/start_pose_orientation_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void StartPoseOrientationScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, std::shared_ptr/* costmap_subscriber */, const std::string & name) @@ -30,14 +30,14 @@ void StartPoseOrientationScorer::configure( name_ = name; logger_ = node->get_logger(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".orientation_tolerance", rclcpp::ParameterValue(M_PI / 2.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".orientation_weight", rclcpp::ParameterValue(1.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".use_orientation_threshold", rclcpp::ParameterValue(false)); orientation_tolerance_ = node->get_parameter(getName() + ".orientation_tolerance").as_double(); diff --git a/nav2_route/src/plugins/edge_cost_functions/time_scorer.cpp b/nav2_route/src/plugins/edge_cost_functions/time_scorer.cpp index a334ed6e18d..096ea963b9a 100644 --- a/nav2_route/src/plugins/edge_cost_functions/time_scorer.cpp +++ b/nav2_route/src/plugins/edge_cost_functions/time_scorer.cpp @@ -21,7 +21,7 @@ namespace nav2_route { void TimeScorer::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, const std::shared_ptr/* tf_buffer */, std::shared_ptr/* costmap_subscriber */, const std::string & name) @@ -30,20 +30,20 @@ void TimeScorer::configure( name_ = name; // Find the tag at high the speed limit information is stored - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".speed_tag", rclcpp::ParameterValue("abs_speed_limit")); speed_tag_ = node->get_parameter(getName() + ".speed_tag").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".time_tag", rclcpp::ParameterValue("abs_time_taken")); prev_time_tag_ = node->get_parameter(getName() + ".time_tag").as_string(); // Find the proportional weight to apply, if multiple cost functions - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".weight", rclcpp::ParameterValue(1.0)); weight_ = static_cast(node->get_parameter(getName() + ".weight").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".max_vel", rclcpp::ParameterValue(0.5)); max_vel_ = static_cast(node->get_parameter(getName() + ".max_vel").as_double()); } diff --git a/nav2_route/src/plugins/graph_file_loaders/geojson_graph_file_loader.cpp b/nav2_route/src/plugins/graph_file_loaders/geojson_graph_file_loader.cpp index 51d0fe9bea2..8b78014ca1f 100644 --- a/nav2_route/src/plugins/graph_file_loaders/geojson_graph_file_loader.cpp +++ b/nav2_route/src/plugins/graph_file_loaders/geojson_graph_file_loader.cpp @@ -23,7 +23,7 @@ namespace nav2_route { void GeoJsonGraphFileLoader::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node) + const nav2::LifecycleNode::SharedPtr node) { RCLCPP_INFO(node->get_logger(), "Configuring geojson graph file loader"); logger_ = node->get_logger(); diff --git a/nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp b/nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp index 64d618cba44..680f7551c5e 100644 --- a/nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp +++ b/nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp @@ -23,7 +23,7 @@ namespace nav2_route { void GeoJsonGraphFileSaver::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node) + const nav2::LifecycleNode::SharedPtr node) { RCLCPP_INFO(node->get_logger(), "Configuring geojson graph file saver"); logger_ = node->get_logger(); diff --git a/nav2_route/src/plugins/route_operations/adjust_speed_limit.cpp b/nav2_route/src/plugins/route_operations/adjust_speed_limit.cpp index 46802194e29..04ec1fa2272 100644 --- a/nav2_route/src/plugins/route_operations/adjust_speed_limit.cpp +++ b/nav2_route/src/plugins/route_operations/adjust_speed_limit.cpp @@ -22,23 +22,23 @@ namespace nav2_route { void AdjustSpeedLimit::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr/* costmap_subscriber */, const std::string & name) { RCLCPP_INFO(node->get_logger(), "Configuring Adjust speed limit operation."); name_ = name; logger_ = node->get_logger(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".speed_tag", rclcpp::ParameterValue("speed_limit")); speed_tag_ = node->get_parameter(getName() + ".speed_tag").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".speed_limit_topic", rclcpp::ParameterValue("speed_limit")); std::string topic = node->get_parameter(getName() + ".speed_tag").as_string(); - speed_limit_pub_ = node->create_publisher(topic, 1); + speed_limit_pub_ = node->create_publisher(topic); speed_limit_pub_->on_activate(); } diff --git a/nav2_route/src/plugins/route_operations/collision_monitor.cpp b/nav2_route/src/plugins/route_operations/collision_monitor.cpp index 9bc7c1c2d7e..01824216671 100644 --- a/nav2_route/src/plugins/route_operations/collision_monitor.cpp +++ b/nav2_route/src/plugins/route_operations/collision_monitor.cpp @@ -23,7 +23,7 @@ namespace nav2_route { void CollisionMonitor::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr costmap_subscriber, const std::string & name) { @@ -33,7 +33,7 @@ void CollisionMonitor::configure( last_check_time_ = clock_->now(); std::string server_costmap_topic = node->get_parameter("costmap_topic").as_string(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".costmap_topic", rclcpp::ParameterValue("local_costmap/costmap_raw")); std::string costmap_topic = node->get_parameter(getName() + ".costmap_topic").as_string(); if (costmap_topic != server_costmap_topic) { @@ -47,26 +47,26 @@ void CollisionMonitor::configure( topic_ = server_costmap_topic; } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".rate", rclcpp::ParameterValue(1.0)); double checking_rate = node->get_parameter(getName() + ".rate").as_double(); checking_duration_ = rclcpp::Duration::from_seconds(1.0 / checking_rate); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".reroute_on_collision", rclcpp::ParameterValue(true)); reroute_on_collision_ = node->get_parameter(getName() + ".reroute_on_collision").as_bool(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".max_cost", rclcpp::ParameterValue(253.0)); max_cost_ = static_cast(node->get_parameter(getName() + ".max_cost").as_double()); // Resolution to check the costmap over (1=every cell, 2=every other cell, etc.) - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".check_resolution", rclcpp::ParameterValue(1)); check_resolution_ = static_cast( node->get_parameter(getName() + ".check_resolution").as_int()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".max_collision_dist", rclcpp::ParameterValue(5.0)); max_collision_dist_ = static_cast( node->get_parameter(getName() + ".max_collision_dist").as_double()); diff --git a/nav2_route/src/plugins/route_operations/rerouting_service.cpp b/nav2_route/src/plugins/route_operations/rerouting_service.cpp index 44cfb4d44a9..2b41a270d3e 100644 --- a/nav2_route/src/plugins/route_operations/rerouting_service.cpp +++ b/nav2_route/src/plugins/route_operations/rerouting_service.cpp @@ -22,7 +22,7 @@ namespace nav2_route { void ReroutingService::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr/* costmap_subscriber */, const std::string & name) { @@ -32,12 +32,12 @@ void ReroutingService::configure( reroute_.store(false); service_ = node->create_service( std::string(node->get_name()) + "/" + getName() + "/reroute", - std::bind( - &ReroutingService::serviceCb, this, - std::placeholders::_1, std::placeholders::_2)); + std::bind(&ReroutingService::serviceCb, this, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); } void ReroutingService::serviceCb( + const std::shared_ptr, const std::shared_ptr/*request*/, std::shared_ptr response) { diff --git a/nav2_route/src/plugins/route_operations/time_marker.cpp b/nav2_route/src/plugins/route_operations/time_marker.cpp index 4da0cbd2c19..dc3c7cf1e78 100644 --- a/nav2_route/src/plugins/route_operations/time_marker.cpp +++ b/nav2_route/src/plugins/route_operations/time_marker.cpp @@ -22,13 +22,13 @@ namespace nav2_route { void TimeMarker::configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr node, + const nav2::LifecycleNode::SharedPtr node, std::shared_ptr/* costmap_subscriber */, const std::string & name) { RCLCPP_INFO(node->get_logger(), "Configuring Adjust speed limit operation."); name_ = name; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, getName() + ".time_tag", rclcpp::ParameterValue("abs_time_taken")); time_tag_ = node->get_parameter(getName() + ".time_tag").as_string(); clock_ = node->get_clock(); diff --git a/nav2_route/src/route_planner.cpp b/nav2_route/src/route_planner.cpp index 1fc005837c2..adb3e772686 100644 --- a/nav2_route/src/route_planner.cpp +++ b/nav2_route/src/route_planner.cpp @@ -25,11 +25,11 @@ namespace nav2_route { void RoutePlanner::configure( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::shared_ptr tf_buffer, const std::shared_ptr costmap_subscriber) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "max_iterations", rclcpp::ParameterValue(0)); max_iterations_ = node->get_parameter("max_iterations").as_int(); diff --git a/nav2_route/src/route_server.cpp b/nav2_route/src/route_server.cpp index aad64e16ec6..2a44005111b 100644 --- a/nav2_route/src/route_server.cpp +++ b/nav2_route/src/route_server.cpp @@ -14,7 +14,7 @@ #include "nav2_route/route_server.hpp" -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using std::placeholders::_1; using std::placeholders::_2; @@ -22,10 +22,10 @@ namespace nav2_route { RouteServer::RouteServer(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("route_server", "", options) +: nav2::LifecycleNode("route_server", "", options) {} -nav2_util::CallbackReturn +nav2::CallbackReturn RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -40,22 +40,20 @@ RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/) auto node = shared_from_this(); graph_vis_publisher_ = node->create_publisher( - "route_graph", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); + "route_graph", nav2::qos::LatchedPublisherQoS()); - compute_route_server_ = std::make_shared( - node, "compute_route", + compute_route_server_ = create_action_server( + "compute_route", std::bind(&RouteServer::computeRoute, this), nullptr, std::chrono::milliseconds(500), true); - compute_and_track_route_server_ = std::make_shared( - node, "compute_and_track_route", + compute_and_track_route_server_ = create_action_server( + "compute_and_track_route", std::bind(&RouteServer::computeAndTrackRoute, this), nullptr, std::chrono::milliseconds(500), true); - set_graph_service_ = std::make_shared>>( + set_graph_service_ = node->create_service( std::string(node->get_name()) + "/set_route_graph", - node, std::bind( &RouteServer::setRouteGraph, this, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); @@ -72,7 +70,7 @@ RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/) max_planning_time_ = node->get_parameter("max_planning_time").as_double(); // Create costmap subscriber - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "costmap_topic", rclcpp::ParameterValue(std::string("global_costmap/costmap_raw"))); std::string costmap_topic = node->get_parameter("costmap_topic").as_string(); @@ -81,7 +79,7 @@ RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/) try { graph_loader_ = std::make_shared(node, tf_, route_frame_); if (!graph_loader_->loadGraphFromParameter(graph_, id_to_graph_map_)) { - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } goal_intent_extractor_ = std::make_shared(); @@ -99,13 +97,13 @@ RouteServer::on_configure(const rclcpp_lifecycle::State & /*state*/) path_converter_->configure(node); } catch (std::exception & e) { RCLCPP_FATAL(get_logger(), "Failed to configure route server: %s", e.what()); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn RouteServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -114,10 +112,10 @@ RouteServer::on_activate(const rclcpp_lifecycle::State & /*state*/) graph_vis_publisher_->on_activate(); graph_vis_publisher_->publish(utils::toMsg(graph_, route_frame_, this->now())); createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn RouteServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -125,10 +123,10 @@ RouteServer::on_deactivate(const rclcpp_lifecycle::State & /*state*/) compute_and_track_route_server_->deactivate(); graph_vis_publisher_->on_deactivate(); destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn RouteServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -144,14 +142,14 @@ RouteServer::on_cleanup(const rclcpp_lifecycle::State & /*state*/) transform_listener_.reset(); tf_.reset(); graph_.clear(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn RouteServer::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } rclcpp::Duration @@ -171,7 +169,7 @@ RouteServer::findPlanningDuration(const rclcpp::Time & start_time) template bool RouteServer::isRequestValid( - std::shared_ptr> & action_server) + typename nav2::SimpleActionServer::SharedPtr & action_server) { if (!action_server || !action_server->is_server_active()) { RCLCPP_DEBUG(get_logger(), "Action server unavailable or inactive. Stopping."); @@ -252,7 +250,7 @@ Route RouteServer::findRoute( template void RouteServer::processRouteRequest( - std::shared_ptr> & action_server) + typename nav2::SimpleActionServer::SharedPtr & action_server) { auto goal = action_server->get_current_goal(); auto result = std::make_shared(); @@ -261,7 +259,7 @@ RouteServer::processRouteRequest( try { while (rclcpp::ok()) { - if (!isRequestValid(action_server)) { + if (!isRequestValid(action_server)) { return; } @@ -352,14 +350,14 @@ void RouteServer::computeRoute() { RCLCPP_INFO(get_logger(), "Computing route to goal."); - processRouteRequest(compute_route_server_); + processRouteRequest(compute_route_server_); } void RouteServer::computeAndTrackRoute() { RCLCPP_INFO(get_logger(), "Computing and tracking route to goal."); - processRouteRequest(compute_and_track_route_server_); + processRouteRequest(compute_and_track_route_server_); } void RouteServer::setRouteGraph( diff --git a/nav2_route/src/route_tracker.cpp b/nav2_route/src/route_tracker.cpp index 7c083a35b3d..ffec246657a 100644 --- a/nav2_route/src/route_tracker.cpp +++ b/nav2_route/src/route_tracker.cpp @@ -18,7 +18,7 @@ namespace nav2_route { void RouteTracker::configure( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, std::shared_ptr tf_buffer, std::shared_ptr costmap_subscriber, std::shared_ptr action_server, @@ -32,16 +32,16 @@ void RouteTracker::configure( action_server_ = action_server; tf_buffer_ = tf_buffer; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "radius_to_achieve_node", rclcpp::ParameterValue(2.0)); radius_threshold_ = node->get_parameter("radius_to_achieve_node").as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "boundary_radius_to_achieve_node", rclcpp::ParameterValue(1.0)); boundary_radius_threshold_ = node->get_parameter("boundary_radius_to_achieve_node").as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "tracker_update_rate", rclcpp::ParameterValue(50.0)); tracker_update_rate_ = node->get_parameter("tracker_update_rate").as_double(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "aggregate_blocked_ids", rclcpp::ParameterValue(false)); aggregate_blocked_ids_ = node->get_parameter("aggregate_blocked_ids").as_bool(); diff --git a/nav2_route/test/performance_benchmarking.cpp b/nav2_route/test/performance_benchmarking.cpp index 9773a8838cc..c6326563fae 100644 --- a/nav2_route/test/performance_benchmarking.cpp +++ b/nav2_route/test/performance_benchmarking.cpp @@ -68,7 +68,7 @@ inline Graph createGraph() int main(int argc, char const * argv[]) { rclcpp::init(argc, argv); - auto node = std::make_shared("route_benchmarking2"); + auto node = std::make_shared("route_benchmarking2"); std::shared_ptr tf_buffer; Graph graph = createGraph(); diff --git a/nav2_route/test/test_collision_operation.cpp b/nav2_route/test/test_collision_operation.cpp index bdb10de1c6f..3dcc99b5465 100644 --- a/nav2_route/test/test_collision_operation.cpp +++ b/nav2_route/test/test_collision_operation.cpp @@ -19,9 +19,9 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/service_client.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_client.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_msgs/msg/speed_limit.hpp" #include "std_srvs/srv/trigger.hpp" #include "nav2_route/operations_manager.hpp" @@ -76,7 +76,7 @@ class CollisionMonitorWrapper : public CollisionMonitor TEST(TestCollisionMonitor, test_lifecycle) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("costmap_topic", rclcpp::ParameterValue("dummy_topic")); CollisionMonitor monitor; std::shared_ptr costmap_subscriber; @@ -87,7 +87,7 @@ TEST(TestCollisionMonitor, test_lifecycle) TEST(TestCollisionMonitor, test_geometric_backout_vector) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("costmap_topic", rclcpp::ParameterValue("local_costmap/costmap_raw")); node->declare_parameter("name.max_collision_dist", rclcpp::ParameterValue(-1.0)); std::shared_ptr costmap_subscriber; @@ -161,9 +161,9 @@ TEST(TestCollisionMonitor, test_geometric_backout_vector) TEST(TestCollisionMonitor, test_costmap_apis) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); node->declare_parameter("costmap_topic", rclcpp::ParameterValue("dummy_topic")); - auto node_thread = std::make_unique(node); + auto node_thread = std::make_unique(node); std::shared_ptr costmap_subscriber; CollisionMonitorWrapper monitor; monitor.configure(node, costmap_subscriber, "name"); diff --git a/nav2_route/test/test_corner_smoothing.cpp b/nav2_route/test/test_corner_smoothing.cpp index 928ab07f3cd..29bf48ee762 100644 --- a/nav2_route/test/test_corner_smoothing.cpp +++ b/nav2_route/test/test_corner_smoothing.cpp @@ -19,7 +19,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/corner_smoothing.hpp" // #include "nav2_route/types.hpp" diff --git a/nav2_route/test/test_edge_scorers.cpp b/nav2_route/test/test_edge_scorers.cpp index 03abe64b788..07af4293d0b 100644 --- a/nav2_route/test/test_edge_scorers.cpp +++ b/nav2_route/test/test_edge_scorers.cpp @@ -19,9 +19,9 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/service_client.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_client.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_route/edge_scorer.hpp" #include "nav2_msgs/srv/dynamic_edges.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" @@ -42,7 +42,7 @@ using namespace nav2_route; // NOLINT TEST(EdgeScorersTest, test_lifecycle) { - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; std::shared_ptr costmap_subscriber; EdgeScorer scorer(node, tf_buffer, costmap_subscriber); @@ -51,7 +51,7 @@ TEST(EdgeScorersTest, test_lifecycle) TEST(EdgeScorersTest, test_api) { // Tests basic API and default behavior. Also covers the DistanceScorer plugin. - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; std::shared_ptr costmap_subscriber; EdgeScorer scorer(node, tf_buffer, costmap_subscriber); @@ -87,12 +87,12 @@ TEST(EdgeScorersTest, test_api) TEST(EdgeScorersTest, test_failed_api) { // Expect failure since plugin does not exist - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"FakeScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "FakeScorer.plugin", rclcpp::ParameterValue(std::string{"FakePluginPath"})); std::shared_ptr costmap_subscriber; @@ -104,14 +104,14 @@ TEST(EdgeScorersTest, test_invalid_edge_scoring) { // Test API for the edge scorer to maintain proper state when a plugin // rejects and edge. Also covers the DynamicEdgesScorer plugin to demonstrate. - auto node = std::make_shared("route_server"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("route_server"); + auto node_thread = std::make_unique(node); auto node2 = std::make_shared("my_node2"); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"DynamicEdgesScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "DynamicEdgesScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::DynamicEdgesScorer"})); @@ -121,7 +121,7 @@ TEST(EdgeScorersTest, test_invalid_edge_scoring) // Send service to set an edge as invalid auto srv_client = - nav2_util::ServiceClient( + nav2::ServiceClient( "route_server/DynamicEdgesScorer/adjust_edges", node2); auto req = std::make_shared(); req->closed_edges.push_back(10u); @@ -174,12 +174,12 @@ TEST(EdgeScorersTest, test_invalid_edge_scoring) TEST(EdgeScorersTest, test_penalty_scoring) { // Test Penalty scorer plugin loading + penalizing on metadata values - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"PenaltyScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "PenaltyScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::PenaltyScorer"})); std::shared_ptr costmap_subscriber; @@ -211,14 +211,14 @@ TEST(EdgeScorersTest, test_penalty_scoring) TEST(EdgeScorersTest, test_costmap_scoring) { // Test Penalty scorer plugin loading + penalizing on metadata values - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); node->declare_parameter("costmap_topic", "dummy_topic"); - auto node_thread = std::make_unique(node); + auto node_thread = std::make_unique(node); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"CostmapScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "CostmapScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::CostmapScorer"})); @@ -326,14 +326,14 @@ TEST(EdgeScorersTest, test_costmap_scoring) TEST(EdgeScorersTest, test_costmap_scoring_alt_profile) { // Test Penalty scorer plugin loading + penalizing on metadata values - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); node->declare_parameter("costmap_topic", "dummy_costmap/costmap_raw"); - auto node_thread = std::make_unique(node); + auto node_thread = std::make_unique(node); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"CostmapScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "CostmapScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::CostmapScorer"})); node->declare_parameter( @@ -429,12 +429,12 @@ TEST(EdgeScorersTest, test_costmap_scoring_alt_profile) TEST(EdgeScorersTest, test_time_scoring) { // Test Time scorer plugin loading - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"TimeScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "TimeScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::TimeScorer"})); @@ -487,12 +487,12 @@ TEST(EdgeScorersTest, test_time_scoring) TEST(EdgeScorersTest, test_semantic_scoring_key) { // Test Time scorer plugin loading - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"SemanticScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "SemanticScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::SemanticScorer"})); @@ -500,12 +500,12 @@ TEST(EdgeScorersTest, test_semantic_scoring_key) classes.push_back("Test"); classes.push_back("Test1"); classes.push_back("Test2"); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "SemanticScorer.semantic_classes", rclcpp::ParameterValue(classes)); for (unsigned int i = 0; i != classes.size(); i++) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "SemanticScorer." + classes[i], rclcpp::ParameterValue(static_cast(i))); } @@ -560,15 +560,15 @@ TEST(EdgeScorersTest, test_semantic_scoring_key) TEST(EdgeScorersTest, test_semantic_scoring_keys) { // Test Time scorer plugin loading - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"SemanticScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "SemanticScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::SemanticScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "SemanticScorer.semantic_key", rclcpp::ParameterValue(std::string{""})); @@ -576,12 +576,12 @@ TEST(EdgeScorersTest, test_semantic_scoring_keys) classes.push_back("Test"); classes.push_back("Test1"); classes.push_back("Test2"); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "SemanticScorer.semantic_classes", rclcpp::ParameterValue(classes)); for (unsigned int i = 0; i != classes.size(); i++) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "SemanticScorer." + classes[i], rclcpp::ParameterValue(static_cast(i))); } @@ -639,19 +639,19 @@ TEST(EdgeScorersTest, test_semantic_scoring_keys) TEST(EdgeScorersTest, test_goal_orientation_threshold) { // Test Penalty scorer plugin loading + penalizing on metadata values - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"GoalOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "GoalOrientationScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::GoalOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "GoalOrientationScorer.orientation_tolerance", rclcpp::ParameterValue(1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "GoalOrientationScorer.use_orientation_threshold", rclcpp::ParameterValue(true)); @@ -708,7 +708,7 @@ TEST(EdgeScorersTest, test_goal_orientation_threshold) TEST(EdgeScorersTest, test_goal_orientation_scoring) { // Test Penalty scorer plugin loading + penalizing on metadata values - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer; double orientation_weight = 100.0; @@ -716,16 +716,16 @@ TEST(EdgeScorersTest, test_goal_orientation_scoring) node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"GoalOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "GoalOrientationScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::GoalOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "GoalOrientationScorer.orientation_tolerance", rclcpp::ParameterValue(1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "GoalOrientationScorer.use_orientation_thershold", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "GoalOrientationScorer.orientation_weight", rclcpp::ParameterValue(orientation_weight)); @@ -783,7 +783,7 @@ TEST(EdgeScorersTest, test_goal_orientation_scoring) TEST(EdgeScorersTest, test_start_pose_orientation_threshold) { // Test Penalty scorer plugin loading + penalizing on metadata values - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer = std::make_shared(node->get_clock()); std::shared_ptr tf_listener = std::make_shared(*tf_buffer); @@ -791,13 +791,13 @@ TEST(EdgeScorersTest, test_start_pose_orientation_threshold) node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"StartPoseOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "StartPoseOrientationScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::StartPoseOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "StartPoseOrientationScorer.orientation_tolerance", rclcpp::ParameterValue(1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "StartPoseOrientationScorer.use_orientation_threshold", rclcpp::ParameterValue(true)); @@ -869,7 +869,7 @@ TEST(EdgeScorersTest, test_start_pose_orientation_threshold) TEST(EdgeScorersTest, test_start_pose_orientation_scoring) { // Test Penalty scorer plugin loading + penalizing on metadata values - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); std::shared_ptr tf_buffer = std::make_shared(node->get_clock()); std::shared_ptr tf_listener = std::make_shared(*tf_buffer); @@ -879,16 +879,16 @@ TEST(EdgeScorersTest, test_start_pose_orientation_scoring) node->declare_parameter( "edge_cost_functions", rclcpp::ParameterValue(std::vector{"StartPoseOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "StartPoseOrientationScorer.plugin", rclcpp::ParameterValue(std::string{"nav2_route::StartPoseOrientationScorer"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "StartPoseOrientationScorer.orientation_tolerance", rclcpp::ParameterValue(1.57)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "StartPoseOrientationScorer.use_orientation_thershold", rclcpp::ParameterValue(false)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "StartPoseOrientationScorer.orientation_weight", rclcpp::ParameterValue(orientation_weight)); diff --git a/nav2_route/test/test_geojson_graph_file_loader.cpp b/nav2_route/test/test_geojson_graph_file_loader.cpp index ae7c3cc3ac5..1205d71c6a7 100644 --- a/nav2_route/test/test_geojson_graph_file_loader.cpp +++ b/nav2_route/test/test_geojson_graph_file_loader.cpp @@ -18,7 +18,7 @@ #include #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp" class RclCppFixture diff --git a/nav2_route/test/test_geojson_graph_file_saver.cpp b/nav2_route/test/test_geojson_graph_file_saver.cpp index 249dbea2ab2..921a0439b2d 100644 --- a/nav2_route/test/test_geojson_graph_file_saver.cpp +++ b/nav2_route/test/test_geojson_graph_file_saver.cpp @@ -18,7 +18,7 @@ #include #include -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp" #include "nav2_route/plugins/graph_file_savers/geojson_graph_file_saver.hpp" diff --git a/nav2_route/test/test_goal_intent_extractor.cpp b/nav2_route/test/test_goal_intent_extractor.cpp index 0ed6827391f..c3ac8d176cc 100644 --- a/nav2_route/test/test_goal_intent_extractor.cpp +++ b/nav2_route/test/test_goal_intent_extractor.cpp @@ -22,9 +22,9 @@ #include "tf2_ros/transform_broadcaster.h" #include "tf2_ros/create_timer_ros.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/service_client.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_client.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_route/goal_intent_extractor.hpp" class RclCppFixture @@ -62,7 +62,7 @@ class GoalIntentExtractorWrapper : public GoalIntentExtractor TEST(GoalIntentExtractorTest, test_obj_lifecycle) { - auto node = std::make_shared("goal_intent_extractor_test"); + auto node = std::make_shared("goal_intent_extractor_test"); GoalIntentExtractor extractor; Graph graph; GraphToIDMap id_map; @@ -72,8 +72,8 @@ TEST(GoalIntentExtractorTest, test_obj_lifecycle) TEST(GoalIntentExtractorTest, test_transform_pose) { - auto node = std::make_shared("goal_intent_extractor_test"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("goal_intent_extractor_test"); + auto node_thread = std::make_unique(node); GoalIntentExtractor extractor; Graph graph; GraphToIDMap id_map; @@ -107,9 +107,9 @@ TEST(GoalIntentExtractorTest, test_transform_pose) TEST(GoalIntentExtractorTest, test_start_goal_finder) { - auto node = std::make_shared("goal_intent_extractor_test"); + auto node = std::make_shared("goal_intent_extractor_test"); node->declare_parameter("enable_nn_search", rclcpp::ParameterValue(false)); - auto node_thread = std::make_unique(node); + auto node_thread = std::make_unique(node); GoalIntentExtractorWrapper extractor; Graph graph; GraphToIDMap id_map; @@ -188,7 +188,7 @@ TEST(GoalIntentExtractorTest, test_start_goal_finder) TEST(GoalIntentExtractorTest, test_pruning) { - auto node = std::make_shared("goal_intent_extractor_test"); + auto node = std::make_shared("goal_intent_extractor_test"); GoalIntentExtractorWrapper extractor; Graph graph; GraphToIDMap id_map; diff --git a/nav2_route/test/test_goal_intent_search.cpp b/nav2_route/test/test_goal_intent_search.cpp index 722273b76f5..a829af0370f 100644 --- a/nav2_route/test/test_goal_intent_search.cpp +++ b/nav2_route/test/test_goal_intent_search.cpp @@ -22,9 +22,9 @@ #include "tf2_ros/transform_broadcaster.h" #include "tf2_ros/create_timer_ros.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/service_client.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_client.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_route/goal_intent_extractor.hpp" class RclCppFixture diff --git a/nav2_route/test/test_graph_loader.cpp b/nav2_route/test/test_graph_loader.cpp index 145d84aea3a..99341852f78 100644 --- a/nav2_route/test/test_graph_loader.cpp +++ b/nav2_route/test/test_graph_loader.cpp @@ -17,8 +17,8 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_route/graph_loader.hpp" #include "tf2_ros/static_transform_broadcaster.h" @@ -34,18 +34,18 @@ using namespace nav2_route; //NOLINT TEST(GraphLoader, test_invalid_plugin) { - auto node = std::make_shared("graph_loader_test"); + auto node = std::make_shared("graph_loader_test"); auto tf = std::make_shared(node->get_clock()); std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/graphs/aws_graph.geojson")); // Set dummy parameter std::string default_plugin = "nav2_route::Dummy"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_file_loader", rclcpp::ParameterValue(default_plugin)); EXPECT_THROW(GraphLoader graph_loader(node, tf, frame), pluginlib::PluginlibException); @@ -53,11 +53,11 @@ TEST(GraphLoader, test_invalid_plugin) TEST(GraphLoader, test_api) { - auto node = std::make_shared("graph_loader_test"); + auto node = std::make_shared("graph_loader_test"); auto tf = std::make_shared(node->get_clock()); std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/graphs/aws_graph.geojson")); @@ -73,7 +73,7 @@ TEST(GraphLoader, test_api) TEST(GraphLoader, test_transformation_api) { - auto node = std::make_shared("graph_loader_test"); + auto node = std::make_shared("graph_loader_test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); auto tf_listener = std::make_shared(*tf); @@ -81,7 +81,7 @@ TEST(GraphLoader, test_transformation_api) std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/graphs/aws_graph.geojson")); @@ -128,13 +128,13 @@ TEST(GraphLoader, test_transformation_api) TEST(GraphLoader, test_transformation_api2) { - auto node = std::make_shared("graph_loader_test"); + auto node = std::make_shared("graph_loader_test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/test/test_graphs/no_frame.json")); diff --git a/nav2_route/test/test_graph_saver.cpp b/nav2_route/test/test_graph_saver.cpp index e6a3913f51a..a6897f11602 100644 --- a/nav2_route/test/test_graph_saver.cpp +++ b/nav2_route/test/test_graph_saver.cpp @@ -18,8 +18,8 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_route/graph_loader.hpp" #include "nav2_route/graph_saver.hpp" #include "tf2_ros/static_transform_broadcaster.h" @@ -36,18 +36,18 @@ using namespace nav2_route; //NOLINT TEST(GraphSaver, test_invalid_plugin) { - auto node = std::make_shared("graph_saver_test"); + auto node = std::make_shared("graph_saver_test"); auto tf = std::make_shared(node->get_clock()); std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/graphs/aws_graph.geojson")); // Set dummy parameter std::string default_plugin = "nav2_route::Dummy"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_file_saver", rclcpp::ParameterValue(default_plugin)); EXPECT_THROW(GraphSaver graph_saver(node, tf, frame), std::runtime_error); @@ -55,11 +55,11 @@ TEST(GraphSaver, test_invalid_plugin) TEST(GraphSaver, test_empty_filename) { - auto node = std::make_shared("graph_saver_test"); + auto node = std::make_shared("graph_saver_test"); auto tf = std::make_shared(node->get_clock()); std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/graphs/aws_graph.geojson")); @@ -76,11 +76,11 @@ TEST(GraphSaver, test_empty_filename) TEST(GraphSaver, test_api) { - auto node = std::make_shared("graph_saver_test"); + auto node = std::make_shared("graph_saver_test"); auto tf = std::make_shared(node->get_clock()); std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/graphs/aws_graph.geojson")); @@ -109,7 +109,7 @@ TEST(GraphSaver, test_api) TEST(GraphSaver, test_transformation_api) { - auto node = std::make_shared("graph_saver_test"); + auto node = std::make_shared("graph_saver_test"); auto tf = std::make_shared(node->get_clock()); tf->setUsingDedicatedThread(true); auto tf_listener = std::make_shared(*tf); @@ -117,7 +117,7 @@ TEST(GraphSaver, test_transformation_api) std::string frame = "map"; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "graph_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_route") + "/graphs/aws_graph.geojson")); diff --git a/nav2_route/test/test_operations.cpp b/nav2_route/test/test_operations.cpp index a8e7301625e..3b35fea6b96 100644 --- a/nav2_route/test/test_operations.cpp +++ b/nav2_route/test/test_operations.cpp @@ -19,9 +19,9 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/service_client.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/service_client.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_msgs/msg/speed_limit.hpp" #include "std_srvs/srv/trigger.hpp" #include "nav2_route/operations_manager.hpp" @@ -40,7 +40,7 @@ using namespace nav2_route; // NOLINT TEST(OperationsManagerTest, test_lifecycle) { - auto node = std::make_shared("operations_manager_test"); + auto node = std::make_shared("operations_manager_test"); std::shared_ptr costmap_subscriber; OperationsManager manager(node, costmap_subscriber); } @@ -48,7 +48,7 @@ TEST(OperationsManagerTest, test_lifecycle) TEST(OperationsManagerTest, test_failed_plugins) { // This plugin does not exist - auto node = std::make_shared("operations_manager_test"); + auto node = std::make_shared("operations_manager_test"); node->declare_parameter("operations", rclcpp::ParameterValue(std::vector{"hi"})); std::shared_ptr costmap_subscriber; EXPECT_THROW(OperationsManager manager(node, costmap_subscriber), std::runtime_error); @@ -56,7 +56,7 @@ TEST(OperationsManagerTest, test_failed_plugins) TEST(OperationsManagerTest, test_find_operations) { - auto node = std::make_shared("operations_manager_test"); + auto node = std::make_shared("operations_manager_test"); std::shared_ptr costmap_subscriber; OperationsManager manager(node, costmap_subscriber); @@ -95,7 +95,7 @@ TEST(OperationsManagerTest, test_find_operations) TEST(OperationsManagerTest, test_find_operations_failure2) { // This plugin does not exist - auto node = std::make_shared("operations_manager_test"); + auto node = std::make_shared("operations_manager_test"); node->declare_parameter("operations", rclcpp::ParameterValue(std::vector{"hi"})); std::shared_ptr costmap_subscriber; EXPECT_THROW(OperationsManager manager(node, costmap_subscriber), std::runtime_error); @@ -103,7 +103,7 @@ TEST(OperationsManagerTest, test_find_operations_failure2) TEST(OperationsManagerTest, test_processing_fail) { - auto node = std::make_shared("operations_manager_test"); + auto node = std::make_shared("operations_manager_test"); // No operation plugins to trigger node->declare_parameter("operations", rclcpp::ParameterValue(std::vector{})); @@ -127,8 +127,8 @@ TEST(OperationsManagerTest, test_processing_fail) TEST(OperationsManagerTest, test_processing_speed_on_status) { - auto node = std::make_shared("operations_manager_test"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("operations_manager_test"); + auto node_thread = std::make_unique(node); std::shared_ptr costmap_subscriber; OperationsManager manager(node, costmap_subscriber); @@ -136,7 +136,6 @@ TEST(OperationsManagerTest, test_processing_speed_on_status) nav2_msgs::msg::SpeedLimit my_msg; auto sub = node->create_subscription( "speed_limit", - rclcpp::QoS(1), [&, this](nav2_msgs::msg::SpeedLimit msg) {got_msg = true; my_msg = msg;}); Node node2; @@ -173,14 +172,14 @@ TEST(OperationsManagerTest, test_processing_speed_on_status) TEST(OperationsManagerTest, test_rerouting_service_on_query) { - auto node = std::make_shared("route_server"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("route_server"); + auto node_thread = std::make_unique(node); auto node_int = std::make_shared("my_node2"); // Enable rerouting service, which conducts on query (not status change) node->declare_parameter( "operations", rclcpp::ParameterValue(std::vector{"ReroutingService"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "ReroutingService.plugin", rclcpp::ParameterValue(std::string{"nav2_route::ReroutingService"})); std::shared_ptr costmap_subscriber; @@ -205,7 +204,7 @@ TEST(OperationsManagerTest, test_rerouting_service_on_query) EXPECT_FALSE(result.reroute); auto srv_client = - nav2_util::ServiceClient( + nav2::ServiceClient( "route_server/ReroutingService/reroute", node_int); auto req = std::make_shared(); auto resp = srv_client.invoke(req, std::chrono::nanoseconds(1000000000)); @@ -224,10 +223,10 @@ TEST(OperationsManagerTest, test_rerouting_service_on_query) TEST(OperationsManagerTest, test_trigger_event_on_graph) { - auto node = std::make_shared("operations_manager_test"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("operations_manager_test"); + auto node_thread = std::make_unique(node); auto node_int = std::make_shared("my_node2"); - auto node_thread_int = std::make_unique(node_int); + auto node_thread_int = std::make_unique(node_int); // Enable trigger event operation, which conducts on node or edge change // when a graph object contains the request for opening a door only. @@ -235,7 +234,7 @@ TEST(OperationsManagerTest, test_trigger_event_on_graph) // Operations Manager as well as the route operations client. node->declare_parameter( "operations", rclcpp::ParameterValue(std::vector{"OpenDoor"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "OpenDoor.plugin", rclcpp::ParameterValue(std::string{"nav2_route::TriggerEvent"})); std::shared_ptr costmap_subscriber; @@ -307,18 +306,18 @@ TEST(OperationsManagerTest, test_trigger_event_on_graph) TEST(OperationsManagerTest, test_trigger_event_on_graph_global_service) { - auto node = std::make_shared("operations_manager_test"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("operations_manager_test"); + auto node_thread = std::make_unique(node); auto node_int = std::make_shared("my_node2"); - auto node_thread_int = std::make_unique(node_int); + auto node_thread_int = std::make_unique(node_int); // Set the global service to use instead of file settings for conflict testing node->declare_parameter( "operations", rclcpp::ParameterValue(std::vector{"OpenDoor"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "OpenDoor.plugin", rclcpp::ParameterValue(std::string{"nav2_route::TriggerEvent"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "OpenDoor.service_name", rclcpp::ParameterValue(std::string{"hello_world"})); std::shared_ptr costmap_subscriber; @@ -395,15 +394,15 @@ TEST(OperationsManagerTest, test_trigger_event_on_graph_global_service) TEST(OperationsManagerTest, test_trigger_event_on_graph_failures) { - auto node = std::make_shared("operations_manager_test"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("operations_manager_test"); + auto node_thread = std::make_unique(node); auto node_int = std::make_shared("my_node2"); // Enable trigger event operation, which conducts on node or edge change // when a graph object contains the request for opening a door only node->declare_parameter( "operations", rclcpp::ParameterValue(std::vector{"OpenDoor"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "OpenDoor.plugin", rclcpp::ParameterValue(std::string{"nav2_route::TriggerEvent"})); std::shared_ptr costmap_subscriber; @@ -444,11 +443,11 @@ TEST(OperationsManagerTest, test_trigger_event_on_graph_failures) TEST(OperationsManagerTest, test_time_marker) { - auto node = std::make_shared("operations_manager_test"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("operations_manager_test"); + auto node_thread = std::make_unique(node); node->declare_parameter( "operations", rclcpp::ParameterValue(std::vector{"TimeMarker"})); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "TimeMarker.plugin", rclcpp::ParameterValue(std::string{"nav2_route::TimeMarker"})); std::shared_ptr costmap_subscriber; @@ -548,7 +547,7 @@ class TestRouteOperations : public nav2_route::RouteOperation { public: void configure( - const rclcpp_lifecycle::LifecycleNode::SharedPtr, + const nav2::LifecycleNode::SharedPtr, std::shared_ptr, const std::string &) override { diff --git a/nav2_route/test/test_path_converter.cpp b/nav2_route/test/test_path_converter.cpp index cadea6ac0c5..91c8ec749a1 100644 --- a/nav2_route/test/test_path_converter.cpp +++ b/nav2_route/test/test_path_converter.cpp @@ -19,7 +19,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/path_converter.hpp" class RclCppFixture @@ -34,12 +34,12 @@ using namespace nav2_route; // NOLINT TEST(PathConverterTest, test_path_converter_api) { - auto node = std::make_shared("edge_scorer_test"); - auto node_thread = std::make_unique(node); + auto node = std::make_shared("edge_scorer_test"); + auto node_thread = std::make_unique(node); nav_msgs::msg::Path path_msg; auto sub = node->create_subscription( - "plan", rclcpp::QoS(1), [&, this](nav_msgs::msg::Path msg) {path_msg = msg;}); + "plan", [&, this](nav_msgs::msg::Path msg) {path_msg = msg;}); PathConverter converter; converter.configure(node); @@ -93,7 +93,7 @@ TEST(PathConverterTest, test_path_converter_api) TEST(PathConverterTest, test_path_single_pt_path) { - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); PathConverter converter; converter.configure(node); @@ -117,7 +117,7 @@ TEST(PathConverterTest, test_path_single_pt_path) TEST(PathConverterTest, test_prev_info_path) { - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); PathConverter converter; converter.configure(node); @@ -146,7 +146,7 @@ TEST(PathConverterTest, test_prev_info_path) TEST(PathConverterTest, test_path_converter_interpolation) { - auto node = std::make_shared("edge_scorer_test"); + auto node = std::make_shared("edge_scorer_test"); PathConverter converter; converter.configure(node); diff --git a/nav2_route/test/test_route_planner.cpp b/nav2_route/test/test_route_planner.cpp index 4c3d53b2153..13c45c08ad1 100644 --- a/nav2_route/test/test_route_planner.cpp +++ b/nav2_route/test/test_route_planner.cpp @@ -19,7 +19,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/route_planner.hpp" #include "nav2_msgs/action/compute_route.hpp" @@ -130,7 +130,7 @@ TEST(RoutePlannerTest, test_route_planner_positive) geometry_msgs::msg::PoseStamped start_pose, goal_pose; RouteRequest route_request; - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); std::shared_ptr tf_buffer; std::shared_ptr collision_checker; RoutePlanner planner; @@ -189,7 +189,7 @@ TEST(RoutePlannerTest, test_route_planner_negative) geometry_msgs::msg::PoseStamped start_pose, goal_pose; RouteRequest route_request; - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); std::shared_ptr tf_buffer; node->declare_parameter("max_iterations", rclcpp::ParameterValue(5)); std::shared_ptr collision_checker; diff --git a/nav2_route/test/test_route_server.cpp b/nav2_route/test/test_route_server.cpp index 17aa3b87a4f..f8906529d31 100644 --- a/nav2_route/test/test_route_server.cpp +++ b/nav2_route/test/test_route_server.cpp @@ -22,9 +22,9 @@ #include "tf2_ros/transform_broadcaster.h" #include "tf2_ros/create_timer_ros.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "std_srvs/srv/trigger.hpp" -#include "nav2_util/service_client.hpp" +#include "nav2_ros_common/service_client.hpp" #include "nav2_core/route_exceptions.hpp" #include "nav2_route/route_tracker.hpp" #include "nav2_route/route_server.hpp" @@ -139,7 +139,7 @@ class RouteServerWrapper : public RouteServer bool isRequestValidWrapper() { - return isRequestValid(compute_and_track_route_server_); + return isRequestValid(compute_and_track_route_server_); } void setNontrivialGraph() @@ -169,12 +169,12 @@ TEST(RouteServerTest, test_set_srv) rclcpp::NodeOptions options; auto server = std::make_shared(options); server->declare_parameter("graph_filepath", rclcpp::ParameterValue(real_filepath)); - auto node_thread = std::make_unique(server); + auto node_thread = std::make_unique(server); auto node2 = std::make_shared("my_node2"); server->startup(); auto srv_client = - nav2_util::ServiceClient( + nav2::ServiceClient( "route_server/set_route_graph", node2); auto req = std::make_shared(); req->graph_filepath = "non/existent/path.json"; @@ -284,7 +284,7 @@ TEST(RouteServerTest, test_complete_action_api) rclcpp::NodeOptions options; auto server = std::make_shared(options); server->declare_parameter("graph_filepath", rclcpp::ParameterValue(real_file)); - auto node_thread = std::make_unique(server); + auto node_thread = std::make_unique(server); server->startup(); // Compute a simple route action request @@ -331,7 +331,7 @@ TEST(RouteServerTest, test_complete_action_api) // Request a reroute auto node_int = std::make_shared("my_node2"); auto srv_client = - nav2_util::ServiceClient( + nav2::ServiceClient( "route_server/ReroutingService/reroute", node_int); auto req = std::make_shared(); auto resp = srv_client.invoke(req, std::chrono::nanoseconds(1000000000)); @@ -359,7 +359,7 @@ TEST(RouteServerTest, test_error_codes) rclcpp::NodeOptions options; auto server = std::make_shared(options); server->declare_parameter("graph_filepath", rclcpp::ParameterValue(real_file)); - auto node_thread = std::make_unique(server); + auto node_thread = std::make_unique(server); server->startup(); // This uses the error code planner rather than the built-in planner diff --git a/nav2_route/test/test_route_tracker.cpp b/nav2_route/test/test_route_tracker.cpp index 33b4dfcc173..9d874a1dc5a 100644 --- a/nav2_route/test/test_route_tracker.cpp +++ b/nav2_route/test/test_route_tracker.cpp @@ -22,7 +22,7 @@ #include "tf2_ros/transform_broadcaster.h" #include "tf2_ros/create_timer_ros.h" #include "tf2_ros/transform_listener.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_core/route_exceptions.hpp" #include "nav2_route/route_tracker.hpp" #include "nav2_route/route_server.hpp" @@ -53,7 +53,7 @@ class RouteTrackerWrapper : public RouteTracker TEST(RouteTrackerTest, test_lifecycle) { - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); RouteTracker tracker; std::shared_ptr costmap_subscriber; @@ -62,7 +62,7 @@ TEST(RouteTrackerTest, test_lifecycle) TEST(RouteTrackerTest, test_get_robot_pose) { - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); auto tf = std::make_shared(node->get_clock()); auto timer_interface = std::make_shared( node->get_node_base_interface(), @@ -87,7 +87,7 @@ TEST(RouteTrackerTest, test_get_robot_pose) TEST(RouteTrackerTest, test_route_start_end) { - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); std::shared_ptr costmap_subscriber; RouteTrackerWrapper tracker; @@ -121,7 +121,7 @@ TEST(RouteTrackerTest, test_route_start_end) TEST(RouteTrackerTest, test_feedback) { - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); std::shared_ptr costmap_subscriber; RouteTrackerWrapper tracker; tracker.configure(node, nullptr, costmap_subscriber, nullptr, "map", "base_link"); @@ -137,7 +137,7 @@ TEST(RouteTrackerTest, test_feedback) TEST(RouteTrackerTest, test_node_achievement_simple) { - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); std::shared_ptr costmap_subscriber; // Test with straight line to do exact analysis easier. More realistic routes in the next test @@ -217,7 +217,7 @@ TEST(RouteTrackerTest, test_node_achievement_simple) TEST(RouteTrackerTest, test_node_achievement) { - auto node = std::make_shared("router_test"); + auto node = std::make_shared("router_test"); std::shared_ptr costmap_subscriber; // Minimum threshold is 2m by default diff --git a/nav2_route/test/test_utils_and_types.cpp b/nav2_route/test/test_utils_and_types.cpp index 6586e834f9f..a6b9a7e37e9 100644 --- a/nav2_route/test/test_utils_and_types.cpp +++ b/nav2_route/test/test_utils_and_types.cpp @@ -19,7 +19,7 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_route/utils.hpp" #include "nav2_route/types.hpp" diff --git a/nav2_rviz_plugins/CMakeLists.txt b/nav2_rviz_plugins/CMakeLists.txt index 2b9e6c30c44..61b852a9708 100644 --- a/nav2_rviz_plugins/CMakeLists.txt +++ b/nav2_rviz_plugins/CMakeLists.txt @@ -21,6 +21,7 @@ find_package(rviz_rendering REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2_geometry_msgs REQUIRED) find_package(visualization_msgs REQUIRED) +find_package(nav2_ros_common REQUIRED) find_package(yaml_cpp_vendor REQUIRED) find_package(yaml-cpp REQUIRED) @@ -72,6 +73,7 @@ target_include_directories(${library_name} PUBLIC ${OGRE_INCLUDE_DIRS} "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -137,6 +139,7 @@ ament_export_dependencies( rviz_rendering std_msgs tf2_geometry_msgs + nav2_ros_common visualization_msgs ) diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp index 837201ea231..0096dd23b66 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/costmap_cost_tool.hpp @@ -23,7 +23,7 @@ #include #include #include -#include "nav2_util/service_client.hpp" +#include "nav2_ros_common/service_client.hpp" namespace nav2_rviz_plugins { @@ -49,8 +49,8 @@ class CostmapCostTool : public rviz_common::Tool private Q_SLOTS: private: - nav2_util::ServiceClient::SharedPtr local_cost_client_; - nav2_util::ServiceClient::SharedPtr global_cost_client_; + nav2::ServiceClient::SharedPtr local_cost_client_; + nav2::ServiceClient::SharedPtr global_cost_client_; // The Node pointer that we need to keep alive for the duration of this plugin. std::shared_ptr node_ptr_; diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp index eeb1af2f630..c96551ae826 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/docking_panel.hpp @@ -99,14 +99,14 @@ private Q_SLOTS: QBasicTimer action_timer_; // The Dock and Undock action client - rclcpp_action::Client::SharedPtr dock_client_; - rclcpp_action::Client::SharedPtr undock_client_; + nav2::ActionClient::SharedPtr dock_client_; + nav2::ActionClient::SharedPtr undock_client_; // Docking / Undocking action feedback subscribers - rclcpp::Subscription::SharedPtr docking_feedback_sub_; - rclcpp::Subscription::SharedPtr undocking_feedback_sub_; - rclcpp::Subscription::SharedPtr docking_goal_status_sub_; - rclcpp::Subscription::SharedPtr undocking_goal_status_sub_; + nav2::Subscription::SharedPtr docking_feedback_sub_; + nav2::Subscription::SharedPtr undocking_feedback_sub_; + nav2::Subscription::SharedPtr docking_goal_status_sub_; + nav2::Subscription::SharedPtr undocking_goal_status_sub_; // Goal related state DockGoalHandle::SharedPtr dock_goal_handle_; @@ -161,8 +161,8 @@ class InitialDockThread : public QThread public: explicit InitialDockThread( - rclcpp_action::Client::SharedPtr & dock_client, - rclcpp_action::Client::SharedPtr & undock_client) + nav2::ActionClient::SharedPtr & dock_client, + nav2::ActionClient::SharedPtr & undock_client) : dock_client_(dock_client), undock_client_(undock_client) {} @@ -196,8 +196,8 @@ class InitialDockThread : public QThread void undockingInactive(); private: - rclcpp_action::Client::SharedPtr dock_client_; - rclcpp_action::Client::SharedPtr undock_client_; + nav2::ActionClient::SharedPtr dock_client_; + nav2::ActionClient::SharedPtr undock_client_; bool dock_active_ = false; bool undock_active_ = false; }; diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp index 2239c47fe5d..3a4cdd9e50f 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/nav2_panel.hpp @@ -120,20 +120,20 @@ private Q_SLOTS: QBasicTimer timer_; // The NavigateToPose action client - rclcpp_action::Client::SharedPtr navigation_action_client_; - rclcpp_action::Client::SharedPtr + nav2::ActionClient::SharedPtr navigation_action_client_; + nav2::ActionClient::SharedPtr waypoint_follower_action_client_; - rclcpp_action::Client::SharedPtr + nav2::ActionClient::SharedPtr nav_through_poses_action_client_; // Navigation action feedback subscribers - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr navigation_feedback_sub_; - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr nav_through_poses_feedback_sub_; - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr navigation_goal_status_sub_; - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr nav_through_poses_goal_status_sub_; // Tf's for initial pose diff --git a/nav2_rviz_plugins/include/nav2_rviz_plugins/route_tool.hpp b/nav2_rviz_plugins/include/nav2_rviz_plugins/route_tool.hpp index 38c75f33466..34bfaec30ee 100644 --- a/nav2_rviz_plugins/include/nav2_rviz_plugins/route_tool.hpp +++ b/nav2_rviz_plugins/include/nav2_rviz_plugins/route_tool.hpp @@ -99,7 +99,7 @@ private Q_SLOTS: private: void update_route_graph(void); - nav2_util::LifecycleNode::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr graph_loader_; std::shared_ptr graph_saver_; std::shared_ptr tf_; @@ -110,7 +110,7 @@ private Q_SLOTS: rclcpp::Publisher::SharedPtr graph_vis_publisher_; - rclcpp::Subscription::SharedPtr + nav2::Subscription::SharedPtr clicked_point_subscription_; unsigned int next_node_id_ = 0; diff --git a/nav2_rviz_plugins/package.xml b/nav2_rviz_plugins/package.xml index 5360d4750ce..91de46fa84c 100644 --- a/nav2_rviz_plugins/package.xml +++ b/nav2_rviz_plugins/package.xml @@ -29,6 +29,7 @@ tf2_geometry_msgs visualization_msgs yaml_cpp_vendor + nav2_ros_common libqt5-core libqt5-gui diff --git a/nav2_rviz_plugins/src/costmap_cost_tool.cpp b/nav2_rviz_plugins/src/costmap_cost_tool.cpp index 1f83425b064..8b4849f4666 100644 --- a/nav2_rviz_plugins/src/costmap_cost_tool.cpp +++ b/nav2_rviz_plugins/src/costmap_cost_tool.cpp @@ -53,12 +53,12 @@ void CostmapCostTool::onInitialize() } rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node(); local_cost_client_ = - std::make_shared>( + std::make_shared>( "local_costmap/get_cost_local_costmap", node, false /* Does not create and spin an internal executor*/); global_cost_client_ = - std::make_shared>( + std::make_shared>( "global_costmap/get_cost_global_costmap", node, false /* Does not create and spin an internal executor*/); diff --git a/nav2_rviz_plugins/src/docking_panel.cpp b/nav2_rviz_plugins/src/docking_panel.cpp index c8a977730ee..2d40b3ae2fd 100644 --- a/nav2_rviz_plugins/src/docking_panel.cpp +++ b/nav2_rviz_plugins/src/docking_panel.cpp @@ -381,7 +381,7 @@ void DockingPanel::onDockingButtonPressed() } // Enable result awareness by providing an empty lambda function - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); send_goal_options.result_callback = [this](const DockGoalHandle::WrappedResult & result) { dock_goal_handle_.reset(); if (result.result->success) { @@ -439,7 +439,7 @@ void DockingPanel::onUndockingButtonPressed() goal_msg.dock_type.c_str()); // Enable result awareness by providing an empty lambda function - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); send_goal_options.result_callback = [this](const UndockGoalHandle::WrappedResult & result) { undock_goal_handle_.reset(); if (result.result->success) { diff --git a/nav2_rviz_plugins/src/nav2_panel.cpp b/nav2_rviz_plugins/src/nav2_panel.cpp index c8d8e0e3408..d7dd3fc5459 100644 --- a/nav2_rviz_plugins/src/nav2_panel.cpp +++ b/nav2_rviz_plugins/src/nav2_panel.cpp @@ -1223,7 +1223,7 @@ Nav2Panel::startWaypointFollowing(std::vector p // Enable result awareness by providing an empty lambda function auto send_goal_options = - rclcpp_action::Client::SendGoalOptions(); + nav2::ActionClient::SendGoalOptions(); send_goal_options.result_callback = [this](auto) { waypoint_follower_goal_handle_.reset(); }; @@ -1281,7 +1281,7 @@ Nav2Panel::startNavThroughPoses(nav_msgs::msg::Goals poses) // Enable result awareness by providing an empty lambda function auto send_goal_options = - rclcpp_action::Client::SendGoalOptions(); + nav2::ActionClient::SendGoalOptions(); send_goal_options.result_callback = [this](auto) { nav_through_poses_goal_handle_.reset(); }; @@ -1327,7 +1327,7 @@ Nav2Panel::startNavigation(geometry_msgs::msg::PoseStamped pose) // Enable result awareness by providing an empty lambda function auto send_goal_options = - rclcpp_action::Client::SendGoalOptions(); + nav2::ActionClient::SendGoalOptions(); send_goal_options.result_callback = [this](auto) { navigation_goal_handle_.reset(); }; diff --git a/nav2_rviz_plugins/src/route_tool.cpp b/nav2_rviz_plugins/src/route_tool.cpp index 767d682887e..7c12dd1b401 100644 --- a/nav2_rviz_plugins/src/route_tool.cpp +++ b/nav2_rviz_plugins/src/route_tool.cpp @@ -29,7 +29,7 @@ RouteTool::RouteTool(QWidget * parent) { // Extend the widget with all attributes and children from UI file ui_->setupUi(this); - node_ = std::make_shared("route_tool_node", "", rclcpp::NodeOptions()); + node_ = std::make_shared("route_tool_node", "", rclcpp::NodeOptions()); node_->configure(); graph_vis_publisher_ = node_->create_publisher( "route_graph", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); diff --git a/nav2_smac_planner/CMakeLists.txt b/nav2_smac_planner/CMakeLists.txt index 4ae1a98ad9e..6d183ac9983 100644 --- a/nav2_smac_planner/CMakeLists.txt +++ b/nav2_smac_planner/CMakeLists.txt @@ -19,6 +19,7 @@ find_package(rcl_interfaces REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) find_package(visualization_msgs REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -47,6 +48,7 @@ target_include_directories(${library_name}_common "$" "$" ${OMPL_INCLUDE_DIRS} + "$" ) target_link_libraries(${library_name}_common PUBLIC ${geometry_msgs_TARGETS} @@ -74,6 +76,7 @@ target_include_directories(${library_name} "$" "$" ${OMPL_INCLUDE_DIRS} + "$" ) target_link_libraries(${library_name} PUBLIC ${library_name}_common @@ -103,6 +106,7 @@ target_include_directories(${library_name}_2d "$" "$" ${OMPL_INCLUDE_DIRS} + "$" ) target_link_libraries(${library_name}_2d PUBLIC ${library_name}_common @@ -132,6 +136,7 @@ target_include_directories(${library_name}_lattice "$" "$" ${OMPL_INCLUDE_DIRS} + "$" ) target_link_libraries(${library_name}_lattice PUBLIC ${library_name}_common @@ -192,6 +197,7 @@ ament_export_dependencies( rclcpp_lifecycle rcl_interfaces tf2 + nav2_ros_common tf2_ros visualization_msgs ) diff --git a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp index 656e069f7e9..9be524e02b1 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp @@ -45,7 +45,7 @@ class GridCollisionChecker GridCollisionChecker( std::shared_ptr costmap, unsigned int num_quantizations, - rclcpp_lifecycle::LifecycleNode::SharedPtr node); + nav2::LifecycleNode::SharedPtr node); /** * @brief A constructor for nav2_smac_planner::GridCollisionChecker diff --git a/nav2_smac_planner/include/nav2_smac_planner/costmap_downsampler.hpp b/nav2_smac_planner/include/nav2_smac_planner/costmap_downsampler.hpp index 21189170298..74dbfdbc5d7 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/costmap_downsampler.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/costmap_downsampler.hpp @@ -51,7 +51,7 @@ class CostmapDownsampler * @param use_min_cost_neighbor If true, min function is used instead of max for downsampling */ void on_configure( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & global_frame, const std::string & topic_name, nav2_costmap_2d::Costmap2D * const costmap, diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp index b386f8d6edb..a5ac6743f42 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp @@ -30,8 +30,8 @@ #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "tf2/utils.hpp" #include "rcl_interfaces/msg/set_parameters_result.hpp" @@ -59,7 +59,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner * @param costmap_ros Costmap2DROS object */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -109,7 +109,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner float _tolerance; int _downsampling_factor; bool _downsample_costmap; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; + nav2::Publisher::SharedPtr _raw_plan_publisher; double _max_planning_time; bool _allow_unknown; int _max_iterations; @@ -120,7 +120,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner std::string _motion_model_for_search; MotionModel _motion_model; std::mutex _mutex; - rclcpp_lifecycle::LifecycleNode::WeakPtr _node; + nav2::LifecycleNode::WeakPtr _node; // Dynamic parameters handler rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp index 0b50c0e15fd..37136af087e 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_hybrid.hpp @@ -30,8 +30,8 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose_array.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "tf2/utils.hpp" namespace nav2_smac_planner @@ -58,7 +58,7 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner * @param costmap_ros Costmap2DROS object */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -125,15 +125,15 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner MotionModel _motion_model; GoalHeadingMode _goal_heading_mode; int _coarse_search_resolution; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr _raw_plan_publisher; + nav2::Publisher::SharedPtr _planned_footprints_publisher; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr _smoothed_footprints_publisher; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr _expansions_publisher; std::mutex _mutex; - rclcpp_lifecycle::LifecycleNode::WeakPtr _node; + nav2::LifecycleNode::WeakPtr _node; // Dynamic parameters handler rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler; diff --git a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp index 8cead0a0145..856734f5221 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/smac_planner_lattice.hpp @@ -29,8 +29,8 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "geometry_msgs/msg/pose_array.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "tf2/utils.hpp" namespace nav2_smac_planner @@ -57,7 +57,7 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner * @param costmap_ros Costmap2DROS object */ void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -112,20 +112,20 @@ class SmacPlannerLattice : public nav2_core::GlobalPlanner int _max_on_approach_iterations; int _terminal_checking_interval; float _tolerance; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; + nav2::Publisher::SharedPtr _raw_plan_publisher; double _max_planning_time; double _lookup_table_size; bool _debug_visualizations; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr _planned_footprints_publisher; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr _smoothed_footprints_publisher; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr _expansions_publisher; GoalHeadingMode _goal_heading_mode; int _coarse_search_resolution; std::mutex _mutex; - rclcpp_lifecycle::LifecycleNode::WeakPtr _node; + nav2::LifecycleNode::WeakPtr _node; // Dynamic parameters handler rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr _dyn_params_handler; diff --git a/nav2_smac_planner/include/nav2_smac_planner/types.hpp b/nav2_smac_planner/include/nav2_smac_planner/types.hpp index f71b4a932f6..3462437c8a2 100644 --- a/nav2_smac_planner/include/nav2_smac_planner/types.hpp +++ b/nav2_smac_planner/include/nav2_smac_planner/types.hpp @@ -20,8 +20,8 @@ #include #include -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_smac_planner { @@ -72,27 +72,27 @@ struct SmootherParams * @param node Ptr to node * @param name Name of plugin */ - void get(std::shared_ptr node, const std::string & name) + void get(nav2::LifecycleNode::SharedPtr node, const std::string & name) { std::string local_name = name + std::string(".smoother."); // Smoother params - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "tolerance", rclcpp::ParameterValue(1e-10)); node->get_parameter(local_name + "tolerance", tolerance_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "max_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(local_name + "max_iterations", max_its_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_data", rclcpp::ParameterValue(0.2)); node->get_parameter(local_name + "w_data", w_data_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_smooth", rclcpp::ParameterValue(0.3)); node->get_parameter(local_name + "w_smooth", w_smooth_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "do_refinement", rclcpp::ParameterValue(true)); node->get_parameter(local_name + "do_refinement", do_refinement_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "refinement_num", rclcpp::ParameterValue(2)); node->get_parameter(local_name + "refinement_num", refinement_num_); } diff --git a/nav2_smac_planner/package.xml b/nav2_smac_planner/package.xml index 8303ffc165f..f8acf8bd6a6 100644 --- a/nav2_smac_planner/package.xml +++ b/nav2_smac_planner/package.xml @@ -27,6 +27,7 @@ tf2_ros tf2 visualization_msgs + nav2_ros_common ament_lint_common ament_lint_auto diff --git a/nav2_smac_planner/src/collision_checker.cpp b/nav2_smac_planner/src/collision_checker.cpp index 98910084d64..76ba33db122 100644 --- a/nav2_smac_planner/src/collision_checker.cpp +++ b/nav2_smac_planner/src/collision_checker.cpp @@ -20,7 +20,7 @@ namespace nav2_smac_planner GridCollisionChecker::GridCollisionChecker( std::shared_ptr costmap_ros, unsigned int num_quantizations, - rclcpp_lifecycle::LifecycleNode::SharedPtr node) + nav2::LifecycleNode::SharedPtr node) : FootprintCollisionChecker(costmap_ros ? costmap_ros->getCostmap() : nullptr) { if (node) { diff --git a/nav2_smac_planner/src/costmap_downsampler.cpp b/nav2_smac_planner/src/costmap_downsampler.cpp index 216aa5c70f5..0082a61f2da 100644 --- a/nav2_smac_planner/src/costmap_downsampler.cpp +++ b/nav2_smac_planner/src/costmap_downsampler.cpp @@ -34,7 +34,7 @@ CostmapDownsampler::~CostmapDownsampler() } void CostmapDownsampler::on_configure( - const nav2_util::LifecycleNode::WeakPtr & node, + const nav2::LifecycleNode::WeakPtr & node, const std::string & global_frame, const std::string & topic_name, nav2_costmap_2d::Costmap2D * const costmap, diff --git a/nav2_smac_planner/src/smac_planner_2d.cpp b/nav2_smac_planner/src/smac_planner_2d.cpp index 1210bc1619c..ff60d7c4a22 100644 --- a/nav2_smac_planner/src/smac_planner_2d.cpp +++ b/nav2_smac_planner/src/smac_planner_2d.cpp @@ -46,7 +46,7 @@ SmacPlanner2D::~SmacPlanner2D() } void SmacPlanner2D::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr/*tf*/, std::shared_ptr costmap_ros) { @@ -61,41 +61,41 @@ void SmacPlanner2D::configure( RCLCPP_INFO(_logger, "Configuring %s of type SmacPlanner2D", name.c_str()); // General planner params - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".tolerance", rclcpp::ParameterValue(0.125)); _tolerance = static_cast(node->get_parameter(name + ".tolerance").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".downsample_costmap", rclcpp::ParameterValue(false)); node->get_parameter(name + ".downsample_costmap", _downsample_costmap); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".downsampling_factor", rclcpp::ParameterValue(1)); node->get_parameter(name + ".downsampling_factor", _downsampling_factor); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".cost_travel_multiplier", rclcpp::ParameterValue(1.0)); node->get_parameter(name + ".cost_travel_multiplier", _search_info.cost_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".allow_unknown", rclcpp::ParameterValue(true)); node->get_parameter(name + ".allow_unknown", _allow_unknown); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); node->get_parameter(name + ".max_iterations", _max_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false)); node->get_parameter(name + ".use_final_approach_orientation", _use_final_approach_orientation); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_planning_time", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".max_planning_time", _max_planning_time); // Note that we need to declare it here to prevent the parameter from being declared in the // dynamic reconfigure callback - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "service_introspection_mode", rclcpp::ParameterValue("disabled")); _motion_model = MotionModel::TWOD; @@ -147,7 +147,7 @@ void SmacPlanner2D::configure( node, _global_frame, topic_name, _costmap, _downsampling_factor); } - _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); + _raw_plan_publisher = node->create_publisher("unsmoothed_plan"); RCLCPP_INFO( _logger, "Configured plugin %s of type SmacPlanner2D with " @@ -439,6 +439,7 @@ SmacPlanner2D::dynamicParametersCallback(std::vector paramete _costmap_downsampler = std::make_unique(); _costmap_downsampler->on_configure( node, _global_frame, topic_name, _costmap, _downsampling_factor); + _costmap_downsampler->on_activate(); } } } diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index ffe69aab305..71e54b47b4d 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -48,7 +48,7 @@ SmacPlannerHybrid::~SmacPlannerHybrid() } void SmacPlannerHybrid::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr/*tf*/, std::shared_ptr costmap_ros) { @@ -68,116 +68,116 @@ void SmacPlannerHybrid::configure( bool smooth_path; // General planner params - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".downsample_costmap", rclcpp::ParameterValue(false)); node->get_parameter(name + ".downsample_costmap", _downsample_costmap); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".downsampling_factor", rclcpp::ParameterValue(1)); node->get_parameter(name + ".downsampling_factor", _downsampling_factor); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".angle_quantization_bins", rclcpp::ParameterValue(72)); node->get_parameter(name + ".angle_quantization_bins", angle_quantizations); _angle_bin_size = 2.0 * M_PI / angle_quantizations; _angle_quantizations = static_cast(angle_quantizations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".tolerance", rclcpp::ParameterValue(0.25)); _tolerance = static_cast(node->get_parameter(name + ".tolerance").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".allow_unknown", rclcpp::ParameterValue(true)); node->get_parameter(name + ".allow_unknown", _allow_unknown); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); node->get_parameter(name + ".max_iterations", _max_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".smooth_path", rclcpp::ParameterValue(true)); node->get_parameter(name + ".smooth_path", smooth_path); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.4)); node->get_parameter(name + ".minimum_turning_radius", _minimum_turning_radius_global_coords); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".allow_primitive_interpolation", rclcpp::ParameterValue(false)); node->get_parameter( name + ".allow_primitive_interpolation", _search_info.allow_primitive_interpolation); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false)); node->get_parameter(name + ".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".change_penalty", rclcpp::ParameterValue(0.0)); node->get_parameter(name + ".change_penalty", _search_info.change_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.2)); node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".cost_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".retrospective_penalty", rclcpp::ParameterValue(0.015)); node->get_parameter(name + ".retrospective_penalty", _search_info.retrospective_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5)); node->get_parameter(name + ".analytic_expansion_ratio", _search_info.analytic_expansion_ratio); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_max_cost", rclcpp::ParameterValue(200.0)); node->get_parameter( name + ".analytic_expansion_max_cost", _search_info.analytic_expansion_max_cost); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_max_cost_override", rclcpp::ParameterValue(false)); node->get_parameter( name + ".analytic_expansion_max_cost_override", _search_info.analytic_expansion_max_cost_override); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".use_quadratic_cost_penalty", rclcpp::ParameterValue(false)); node->get_parameter( name + ".use_quadratic_cost_penalty", _search_info.use_quadratic_cost_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".downsample_obstacle_heuristic", rclcpp::ParameterValue(true)); node->get_parameter( name + ".downsample_obstacle_heuristic", _search_info.downsample_obstacle_heuristic); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_max_length", rclcpp::ParameterValue(3.0)); node->get_parameter(name + ".analytic_expansion_max_length", analytic_expansion_max_length_m); _search_info.analytic_expansion_max_length = analytic_expansion_max_length_m / _costmap->getResolution(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_planning_time", rclcpp::ParameterValue(5.0)); node->get_parameter(name + ".max_planning_time", _max_planning_time); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0)); node->get_parameter(name + ".lookup_table_size", _lookup_table_size); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".debug_visualizations", rclcpp::ParameterValue(false)); node->get_parameter(name + ".debug_visualizations", _debug_visualizations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".motion_model_for_search", rclcpp::ParameterValue(std::string("DUBIN"))); node->get_parameter(name + ".motion_model_for_search", _motion_model_for_search); // Note that we need to declare it here to prevent the parameter from being declared in the // dynamic reconfigure callback - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "service_introspection_mode", rclcpp::ParameterValue("disabled")); std::string goal_heading_type; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".goal_heading_mode", rclcpp::ParameterValue("DEFAULT")); node->get_parameter(name + ".goal_heading_mode", goal_heading_type); _goal_heading_mode = fromStringToGH(goal_heading_type); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".coarse_search_resolution", rclcpp::ParameterValue(1)); node->get_parameter(name + ".coarse_search_resolution", _coarse_search_resolution); @@ -288,15 +288,15 @@ void SmacPlannerHybrid::configure( node, _global_frame, topic_name, _costmap, _downsampling_factor); } - _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); + _raw_plan_publisher = node->create_publisher("unsmoothed_plan"); if (_debug_visualizations) { - _expansions_publisher = node->create_publisher("expansions", 1); + _expansions_publisher = node->create_publisher("expansions"); _planned_footprints_publisher = node->create_publisher( - "planned_footprints", 1); + "planned_footprints"); _smoothed_footprints_publisher = node->create_publisher( - "smoothed_footprints", 1); + "smoothed_footprints"); } RCLCPP_INFO( @@ -836,6 +836,7 @@ SmacPlannerHybrid::dynamicParametersCallback(std::vector para _costmap_downsampler = std::make_unique(); _costmap_downsampler->on_configure( node, _global_frame, topic_name, _costmap, _downsampling_factor); + _costmap_downsampler->on_activate(); } } diff --git a/nav2_smac_planner/src/smac_planner_lattice.cpp b/nav2_smac_planner/src/smac_planner_lattice.cpp index 759d6b34768..d689507e8f4 100644 --- a/nav2_smac_planner/src/smac_planner_lattice.cpp +++ b/nav2_smac_planner/src/smac_planner_lattice.cpp @@ -44,7 +44,7 @@ SmacPlannerLattice::~SmacPlannerLattice() } void SmacPlannerLattice::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr/*tf*/, std::shared_ptr costmap_ros) { @@ -63,90 +63,90 @@ void SmacPlannerLattice::configure( double analytic_expansion_max_length_m; bool smooth_path; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".tolerance", rclcpp::ParameterValue(0.25)); _tolerance = static_cast(node->get_parameter(name + ".tolerance").as_double()); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".allow_unknown", rclcpp::ParameterValue(true)); node->get_parameter(name + ".allow_unknown", _allow_unknown); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); node->get_parameter(name + ".max_iterations", _max_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000)); node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); node->get_parameter(name + ".terminal_checking_interval", _terminal_checking_interval); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".smooth_path", rclcpp::ParameterValue(true)); node->get_parameter(name + ".smooth_path", smooth_path); // Default to a well rounded model: 16 bin, 0.4m turning radius, ackermann model - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".lattice_filepath", rclcpp::ParameterValue( ament_index_cpp::get_package_share_directory("nav2_smac_planner") + "/sample_primitives/5cm_resolution/0.5m_turning_radius/ackermann/output.json")); node->get_parameter(name + ".lattice_filepath", _search_info.lattice_filepath); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".cache_obstacle_heuristic", rclcpp::ParameterValue(false)); node->get_parameter(name + ".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".change_penalty", rclcpp::ParameterValue(0.05)); node->get_parameter(name + ".change_penalty", _search_info.change_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.05)); node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".cost_penalty", rclcpp::ParameterValue(2.0)); node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".retrospective_penalty", rclcpp::ParameterValue(0.015)); node->get_parameter(name + ".retrospective_penalty", _search_info.retrospective_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".rotation_penalty", rclcpp::ParameterValue(5.0)); node->get_parameter(name + ".rotation_penalty", _search_info.rotation_penalty); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_ratio", rclcpp::ParameterValue(3.5)); node->get_parameter(name + ".analytic_expansion_ratio", _search_info.analytic_expansion_ratio); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_max_cost", rclcpp::ParameterValue(200.0)); node->get_parameter( name + ".analytic_expansion_max_cost", _search_info.analytic_expansion_max_cost); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_max_cost_override", rclcpp::ParameterValue(false)); node->get_parameter( name + ".analytic_expansion_max_cost_override", _search_info.analytic_expansion_max_cost_override); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".analytic_expansion_max_length", rclcpp::ParameterValue(3.0)); node->get_parameter(name + ".analytic_expansion_max_length", analytic_expansion_max_length_m); _search_info.analytic_expansion_max_length = analytic_expansion_max_length_m / _costmap->getResolution(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".max_planning_time", rclcpp::ParameterValue(5.0)); node->get_parameter(name + ".max_planning_time", _max_planning_time); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0)); node->get_parameter(name + ".lookup_table_size", _lookup_table_size); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".allow_reverse_expansion", rclcpp::ParameterValue(false)); node->get_parameter(name + ".allow_reverse_expansion", _search_info.allow_reverse_expansion); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".debug_visualizations", rclcpp::ParameterValue(false)); node->get_parameter(name + ".debug_visualizations", _debug_visualizations); std::string goal_heading_type; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".goal_heading_mode", rclcpp::ParameterValue("DEFAULT")); node->get_parameter(name + ".goal_heading_mode", goal_heading_type); _goal_heading_mode = fromStringToGH(goal_heading_type); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".coarse_search_resolution", rclcpp::ParameterValue(1)); node->get_parameter(name + ".coarse_search_resolution", _coarse_search_resolution); @@ -237,15 +237,15 @@ void SmacPlannerLattice::configure( _smoother->initialize(_metadata.min_turning_radius); } - _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); + _raw_plan_publisher = node->create_publisher("unsmoothed_plan"); if (_debug_visualizations) { - _expansions_publisher = node->create_publisher("expansions", 1); + _expansions_publisher = node->create_publisher("expansions"); _planned_footprints_publisher = node->create_publisher( - "planned_footprints", 1); + "planned_footprints"); _smoothed_footprints_publisher = node->create_publisher( - "smoothed_footprints", 1); + "smoothed_footprints"); } RCLCPP_INFO( diff --git a/nav2_smac_planner/test/deprecated/options.hpp b/nav2_smac_planner/test/deprecated/options.hpp index 5d33223dc41..7900c2ad118 100644 --- a/nav2_smac_planner/test/deprecated/options.hpp +++ b/nav2_smac_planner/test/deprecated/options.hpp @@ -16,8 +16,8 @@ #define DEPRECATED__OPTIONS_HPP_ #include -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_smac_planner { @@ -40,24 +40,24 @@ struct SmootherParams * @param node_ Ptr to node * @param name Name of plugin */ - void get(rclcpp_lifecycle::LifecycleNode * node, const std::string & name) + void get(nav2::LifecycleNode * node, const std::string & name) { std::string local_name = name + std::string(".smoother.smoother."); // Smoother params - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_curve", rclcpp::ParameterValue(1.5)); node->get_parameter(local_name + "w_curve", curvature_weight); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_cost", rclcpp::ParameterValue(0.0)); node->get_parameter(local_name + "w_cost", costmap_weight); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_dist", rclcpp::ParameterValue(0.0)); node->get_parameter(local_name + "w_dist", distance_weight); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "w_smooth", rclcpp::ParameterValue(15000.0)); node->get_parameter(local_name + "w_smooth", smooth_weight); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "cost_scaling_factor", rclcpp::ParameterValue(10.0)); node->get_parameter(local_name + "cost_scaling_factor", costmap_factor); } @@ -110,36 +110,36 @@ struct OptimizerParams * @param node_ Ptr to node * @param name Name of plugin */ - void get(rclcpp_lifecycle::LifecycleNode * node, const std::string & name) + void get(nav2::LifecycleNode * node, const std::string & name) { std::string local_name = name + std::string(".smoother.optimizer.advanced."); // Optimizer advanced params - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "min_line_search_step_size", rclcpp::ParameterValue(1e-20)); node->get_parameter( local_name + "min_line_search_step_size", min_line_search_step_size); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "max_num_line_search_step_size_iterations", rclcpp::ParameterValue(50)); node->get_parameter( local_name + "max_num_line_search_step_size_iterations", max_num_line_search_step_size_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "line_search_sufficient_function_decrease", rclcpp::ParameterValue(1e-20)); node->get_parameter( local_name + "line_search_sufficient_function_decrease", line_search_sufficient_function_decrease); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "max_num_line_search_direction_restarts", rclcpp::ParameterValue(10)); node->get_parameter( local_name + "max_num_line_search_direction_restarts", max_num_line_search_direction_restarts); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "max_line_search_step_expansion", rclcpp::ParameterValue(50)); node->get_parameter( @@ -164,27 +164,27 @@ struct OptimizerParams * @param node_ Ptr to node * @param name Name of plugin */ - void get(rclcpp_lifecycle::LifecycleNode * node, const std::string & name) + void get(nav2::LifecycleNode * node, const std::string & name) { std::string local_name = name + std::string(".smoother.optimizer."); // Optimizer params - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "param_tol", rclcpp::ParameterValue(1e-15)); node->get_parameter(local_name + "param_tol", param_tol); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "fn_tol", rclcpp::ParameterValue(1e-7)); node->get_parameter(local_name + "fn_tol", fn_tol); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "gradient_tol", rclcpp::ParameterValue(1e-10)); node->get_parameter(local_name + "gradient_tol", gradient_tol); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "max_iterations", rclcpp::ParameterValue(500)); node->get_parameter(local_name + "max_iterations", max_iterations); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "max_time", rclcpp::ParameterValue(0.100)); node->get_parameter(local_name + "max_time", max_time); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, local_name + "debug_optimizer", rclcpp::ParameterValue(false)); node->get_parameter(local_name + "debug_optimizer", debug); diff --git a/nav2_smac_planner/test/test_a_star.cpp b/nav2_smac_planner/test/test_a_star.cpp index 3c9bd9269bd..751e1f2f6c8 100644 --- a/nav2_smac_planner/test/test_a_star.cpp +++ b/nav2_smac_planner/test/test_a_star.cpp @@ -22,7 +22,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/node_lattice.hpp" #include "nav2_smac_planner/a_star.hpp" @@ -31,7 +31,7 @@ TEST(AStarTest, test_a_star_2d) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; nav2_smac_planner::AStarAlgorithm a_star( nav2_smac_planner::MotionModel::TWOD, info); @@ -154,7 +154,7 @@ TEST(AStarTest, test_a_star_2d) TEST(AStarTest, test_a_star_se2) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 0.1; info.non_straight_penalty = 1.1; @@ -231,7 +231,7 @@ TEST(AStarTest, test_a_star_se2) TEST(AStarTest, test_a_star_analytic_expansion) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 0.0; info.non_straight_penalty = 1.1; @@ -293,7 +293,7 @@ TEST(AStarTest, test_a_star_analytic_expansion) TEST(AStarTest, test_a_star_lattice) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 0.05; info.non_straight_penalty = 1.05; @@ -368,7 +368,7 @@ TEST(AStarTest, test_a_star_lattice) TEST(AStarTest, test_se2_single_pose_path) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 0.1; info.non_straight_penalty = 1.1; @@ -434,7 +434,7 @@ TEST(AStarTest, test_se2_single_pose_path) TEST(AStarTest, test_goal_heading_mode) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 0.1; info.non_straight_penalty = 1.1; diff --git a/nav2_smac_planner/test/test_collision_checker.cpp b/nav2_smac_planner/test/test_collision_checker.cpp index 9c039e159d9..48e65389dbf 100644 --- a/nav2_smac_planner/test/test_collision_checker.cpp +++ b/nav2_smac_planner/test/test_collision_checker.cpp @@ -24,7 +24,7 @@ using namespace nav2_costmap_2d; // NOLINT TEST(collision_footprint, test_basic) { - auto node = std::make_shared("testA"); + auto node = std::make_shared("testA"); nav2_costmap_2d::Costmap2D * costmap_ = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0, 0, 0); geometry_msgs::msg::Point p1; @@ -58,7 +58,7 @@ TEST(collision_footprint, test_basic) TEST(collision_footprint, test_point_cost) { - auto node = std::make_shared("testB"); + auto node = std::make_shared("testB"); nav2_costmap_2d::Costmap2D * costmap_ = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0, 0, 0); // Convert raw costmap into a costmap ros object @@ -79,7 +79,7 @@ TEST(collision_footprint, test_point_cost) TEST(collision_footprint, test_world_to_map) { - auto node = std::make_shared("testC"); + auto node = std::make_shared("testC"); nav2_costmap_2d::Costmap2D * costmap_ = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0, 0, 0); // Convert raw costmap into a costmap ros object @@ -111,7 +111,7 @@ TEST(collision_footprint, test_world_to_map) TEST(collision_footprint, test_footprint_at_pose_with_movement) { - auto node = std::make_shared("testD"); + auto node = std::make_shared("testD"); nav2_costmap_2d::Costmap2D * costmap_ = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0, 0, 254); for (unsigned int i = 40; i <= 60; ++i) { @@ -165,7 +165,7 @@ TEST(collision_footprint, test_footprint_at_pose_with_movement) TEST(collision_footprint, test_point_and_line_cost) { - auto node = std::make_shared("testE"); + auto node = std::make_shared("testE"); nav2_costmap_2d::Costmap2D * costmap_ = new nav2_costmap_2d::Costmap2D( 100, 100, 0.10000, 0, 0.0, 128.0); diff --git a/nav2_smac_planner/test/test_costmap_downsampler.cpp b/nav2_smac_planner/test/test_costmap_downsampler.cpp index 3011699b854..1fd6e0aee26 100644 --- a/nav2_smac_planner/test/test_costmap_downsampler.cpp +++ b/nav2_smac_planner/test/test_costmap_downsampler.cpp @@ -18,12 +18,12 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smac_planner/costmap_downsampler.hpp" TEST(CostmapDownsampler, costmap_downsample_test) { - nav2_util::LifecycleNode::SharedPtr node = std::make_shared( + nav2::LifecycleNode::SharedPtr node = std::make_shared( "CostmapDownsamplerTest"); nav2_smac_planner::CostmapDownsampler downsampler; diff --git a/nav2_smac_planner/test/test_goal_manager.cpp b/nav2_smac_planner/test/test_goal_manager.cpp index 80f71b3a688..d8827e92c29 100644 --- a/nav2_smac_planner/test/test_goal_manager.cpp +++ b/nav2_smac_planner/test/test_goal_manager.cpp @@ -20,7 +20,7 @@ #include "nav2_smac_planner/goal_manager.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smac_planner/collision_checker.hpp" using namespace nav2_smac_planner; // NOLINT @@ -33,7 +33,7 @@ using CoordinateVector = GoalManagerHybrid::CoordinateVector; TEST(GoalManagerTest, test_goal_manager) { - auto node = std::make_shared("test_node"); + auto node = std::make_shared("test_node"); auto costmapA = new nav2_costmap_2d::Costmap2D(100, 100, 0.1, 0.0, 0.0, 0); diff --git a/nav2_smac_planner/test/test_node2d.cpp b/nav2_smac_planner/test/test_node2d.cpp index 526a263a526..7ec2bfd4902 100644 --- a/nav2_smac_planner/test/test_node2d.cpp +++ b/nav2_smac_planner/test/test_node2d.cpp @@ -20,13 +20,13 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smac_planner/node_2d.hpp" #include "nav2_smac_planner/collision_checker.hpp" TEST(Node2DTest, test_node_2d) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); nav2_costmap_2d::Costmap2D costmapA(10, 10, 0.05, 0.0, 0.0, 0); // Convert raw costmap into a costmap ros object @@ -103,7 +103,7 @@ TEST(Node2DTest, test_node_2d) TEST(Node2DTest, test_node_2d_neighbors) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; unsigned int size_x = 10u; unsigned int size_y = 10u; diff --git a/nav2_smac_planner/test/test_nodehybrid.cpp b/nav2_smac_planner/test/test_nodehybrid.cpp index 18dd18260a7..cf452cb984b 100644 --- a/nav2_smac_planner/test/test_nodehybrid.cpp +++ b/nav2_smac_planner/test/test_nodehybrid.cpp @@ -22,14 +22,14 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/collision_checker.hpp" #include "nav2_smac_planner/types.hpp" TEST(NodeHybridTest, test_node_hybrid) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 0.1; info.non_straight_penalty = 1.1; @@ -143,7 +143,7 @@ TEST(NodeHybridTest, test_node_hybrid) TEST(NodeHybridTest, test_obstacle_heuristic) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 0.1; info.non_straight_penalty = 1.1; @@ -304,7 +304,7 @@ TEST(NodeHybridTest, test_interpolation_prims2) TEST(NodeHybridTest, test_node_reeds_neighbors) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); nav2_smac_planner::SearchInfo info; info.change_penalty = 1.2; info.non_straight_penalty = 1.4; diff --git a/nav2_smac_planner/test/test_nodelattice.cpp b/nav2_smac_planner/test/test_nodelattice.cpp index 7c6fbe88566..9e8bae98604 100644 --- a/nav2_smac_planner/test/test_nodelattice.cpp +++ b/nav2_smac_planner/test/test_nodelattice.cpp @@ -22,7 +22,7 @@ #include "nav2_smac_planner/node_lattice.hpp" #include "gtest/gtest.h" #include "ament_index_cpp/get_package_share_directory.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" using json = nlohmann::json; @@ -170,7 +170,7 @@ TEST(NodeLatticeTest, test_node_lattice_conversions) TEST(NodeLatticeTest, test_node_lattice) { - auto node = std::make_shared("test"); + auto node = std::make_shared("test"); std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); std::string filePath = pkg_share_dir + @@ -254,7 +254,7 @@ TEST(NodeLatticeTest, test_node_lattice) TEST(NodeLatticeTest, test_get_neighbors) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); std::string filePath = pkg_share_dir + @@ -312,7 +312,7 @@ TEST(NodeLatticeTest, test_get_neighbors) TEST(NodeLatticeTest, test_node_lattice_custom_footprint) { - auto lnode = std::make_shared("test"); + auto lnode = std::make_shared("test"); std::string pkg_share_dir = ament_index_cpp::get_package_share_directory("nav2_smac_planner"); std::string filePath = pkg_share_dir + diff --git a/nav2_smac_planner/test/test_smac_2d.cpp b/nav2_smac_planner/test/test_smac_2d.cpp index 35ef1a90d12..bbad2044d3f 100644 --- a/nav2_smac_planner/test/test_smac_2d.cpp +++ b/nav2_smac_planner/test/test_smac_2d.cpp @@ -27,7 +27,7 @@ #include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/smac_planner_2d.hpp" #include "nav2_smac_planner/smac_planner_hybrid.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" // SMAC smoke tests for plugin-level issues rather than algorithms @@ -35,8 +35,8 @@ // System tests in nav2_system_tests will actually plan with this work TEST(SmacTest, test_smac_2d) { - rclcpp_lifecycle::LifecycleNode::SharedPtr node2D = - std::make_shared("Smac2DTest"); + nav2::LifecycleNode::SharedPtr node2D = + std::make_shared("Smac2DTest"); std::shared_ptr costmap_ros = std::make_shared("global_costmap"); @@ -49,6 +49,9 @@ TEST(SmacTest, test_smac_2d) { node2D->declare_parameter("test.downsampling_factor", 2); node2D->set_parameter(rclcpp::Parameter("test.downsampling_factor", 2)); + node2D->configure(); + node2D->activate(); + auto dummy_cancel_checker = []() { return false; }; @@ -81,18 +84,23 @@ TEST(SmacTest, test_smac_2d) { planner_2d.reset(); costmap_ros->on_cleanup(rclcpp_lifecycle::State()); + node2D->deactivate(); + node2D->cleanup(); node2D.reset(); costmap_ros.reset(); } TEST(SmacTest, test_smac_2d_reconfigure) { - rclcpp_lifecycle::LifecycleNode::SharedPtr node2D = - std::make_shared("Smac2DTest"); + nav2::LifecycleNode::SharedPtr node2D = + std::make_shared("Smac2DTest"); std::shared_ptr costmap_ros = std::make_shared("global_costmap"); costmap_ros->on_configure(rclcpp_lifecycle::State()); + node2D->configure(); + node2D->activate(); + auto planner_2d = std::make_unique(); planner_2d->configure(node2D, "test", nullptr, costmap_ros); planner_2d->activate(); diff --git a/nav2_smac_planner/test/test_smac_hybrid.cpp b/nav2_smac_planner/test/test_smac_hybrid.cpp index 28c7719355a..f356bf04227 100644 --- a/nav2_smac_planner/test/test_smac_hybrid.cpp +++ b/nav2_smac_planner/test/test_smac_hybrid.cpp @@ -21,7 +21,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/a_star.hpp" @@ -65,14 +65,17 @@ class HybridWrap : public nav2_smac_planner::SmacPlannerHybrid TEST(SmacTest, test_smac_se2) { - rclcpp_lifecycle::LifecycleNode::SharedPtr nodeSE2 = - std::make_shared("SmacSE2Test"); + nav2::LifecycleNode::SharedPtr nodeSE2 = + std::make_shared("SmacSE2Test"); nodeSE2->declare_parameter("test.debug_visualizations", rclcpp::ParameterValue(true)); std::shared_ptr costmap_ros = std::make_shared("global_costmap"); costmap_ros->on_configure(rclcpp_lifecycle::State()); + nodeSE2->configure(); + nodeSE2->activate(); + nodeSE2->declare_parameter("test.downsample_costmap", true); nodeSE2->set_parameter(rclcpp::Parameter("test.downsample_costmap", true)); nodeSE2->declare_parameter("test.downsampling_factor", 2); @@ -149,19 +152,24 @@ TEST(SmacTest, test_smac_se2) planner.reset(); costmap_ros->on_cleanup(rclcpp_lifecycle::State()); + nodeSE2->deactivate(); + nodeSE2->cleanup(); costmap_ros.reset(); nodeSE2.reset(); } TEST(SmacTest, test_smac_se2_reconfigure) { - rclcpp_lifecycle::LifecycleNode::SharedPtr nodeSE2 = - std::make_shared("SmacSE2Test"); + nav2::LifecycleNode::SharedPtr nodeSE2 = + std::make_shared("SmacSE2Test"); std::shared_ptr costmap_ros = std::make_shared("global_costmap"); costmap_ros->on_configure(rclcpp_lifecycle::State()); + nodeSE2->configure(); + nodeSE2->activate(); + auto planner = std::make_unique(); planner->configure(nodeSE2, "test", nullptr, costmap_ros); planner->activate(); diff --git a/nav2_smac_planner/test/test_smac_lattice.cpp b/nav2_smac_planner/test/test_smac_lattice.cpp index a1eb918502f..d9f33f7050e 100644 --- a/nav2_smac_planner/test/test_smac_lattice.cpp +++ b/nav2_smac_planner/test/test_smac_lattice.cpp @@ -21,7 +21,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/a_star.hpp" @@ -64,8 +64,8 @@ class LatticeWrap : public nav2_smac_planner::SmacPlannerLattice TEST(SmacTest, test_smac_lattice) { - rclcpp_lifecycle::LifecycleNode::SharedPtr nodeLattice = - std::make_shared("SmacLatticeTest"); + nav2::LifecycleNode::SharedPtr nodeLattice = + std::make_shared("SmacLatticeTest"); nodeLattice->declare_parameter("test.debug_visualizations", rclcpp::ParameterValue(true)); std::shared_ptr costmap_ros = @@ -142,8 +142,8 @@ TEST(SmacTest, test_smac_lattice) TEST(SmacTest, test_smac_lattice_reconfigure) { - rclcpp_lifecycle::LifecycleNode::SharedPtr nodeLattice = - std::make_shared("SmacLatticeTest"); + nav2::LifecycleNode::SharedPtr nodeLattice = + std::make_shared("SmacLatticeTest"); std::shared_ptr costmap_ros = std::make_shared("global_costmap"); diff --git a/nav2_smac_planner/test/test_smoother.cpp b/nav2_smac_planner/test/test_smoother.cpp index 89f28f15d56..6c223176c23 100644 --- a/nav2_smac_planner/test/test_smoother.cpp +++ b/nav2_smac_planner/test/test_smoother.cpp @@ -22,7 +22,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smac_planner/node_hybrid.hpp" #include "nav2_smac_planner/a_star.hpp" #include "nav2_smac_planner/collision_checker.hpp" @@ -46,8 +46,8 @@ class SmootherWrapper : public nav2_smac_planner::Smoother TEST(SmootherTest, test_full_smoother) { - rclcpp_lifecycle::LifecycleNode::SharedPtr node = - std::make_shared("SmacSmootherTest"); + nav2::LifecycleNode::SharedPtr node = + std::make_shared("SmacSmootherTest"); nav2_smac_planner::SmootherParams params; params.get(node, "test"); double maxtime = 1.0; diff --git a/nav2_smoother/CMakeLists.txt b/nav2_smoother/CMakeLists.txt index 7e93a035c08..5ce209349fa 100644 --- a/nav2_smoother/CMakeLists.txt +++ b/nav2_smoother/CMakeLists.txt @@ -15,6 +15,7 @@ find_package(rclcpp_components REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -28,7 +29,8 @@ add_library(${library_name} SHARED target_include_directories(${library_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${library_name} PUBLIC nav2_core::nav2_core nav2_costmap_2d::nav2_costmap_2d_client @@ -40,6 +42,7 @@ target_link_libraries(${library_name} PUBLIC rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common ) target_link_libraries(${library_name} PRIVATE nav_2d_utils::conversions @@ -55,7 +58,8 @@ add_executable(${executable_name} target_include_directories(${executable_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${executable_name} PRIVATE rclcpp::rclcpp ${library_name}) # Simple Smoother plugin @@ -65,7 +69,8 @@ add_library(simple_smoother SHARED target_include_directories(simple_smoother PUBLIC "$" - "$") + "$" + "$") target_link_libraries(simple_smoother PUBLIC angles::angles nav2_core::nav2_core @@ -77,6 +82,7 @@ target_link_libraries(simple_smoother PUBLIC rclcpp_lifecycle::rclcpp_lifecycle tf2::tf2 tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common ) target_link_libraries(simple_smoother PRIVATE pluginlib::pluginlib @@ -89,7 +95,8 @@ add_library(savitzky_golay_smoother SHARED target_include_directories(savitzky_golay_smoother PUBLIC "$" - "$") + "$" + "$") target_link_libraries(savitzky_golay_smoother PUBLIC angles::angles nav2_core::nav2_core @@ -100,6 +107,7 @@ target_link_libraries(savitzky_golay_smoother PUBLIC rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle tf2::tf2 + nav2_ros_common::nav2_ros_common tf2_ros::tf2_ros ) target_link_libraries(savitzky_golay_smoother PRIVATE @@ -151,6 +159,7 @@ ament_export_dependencies( nav2_util pluginlib rclcpp + nav2_ros_common rclcpp_lifecycle tf2 tf2_ros diff --git a/nav2_smoother/include/nav2_smoother/nav2_smoother.hpp b/nav2_smoother/include/nav2_smoother/nav2_smoother.hpp index fac9ffe3af6..fdf8db4ffad 100644 --- a/nav2_smoother/include/nav2_smoother/nav2_smoother.hpp +++ b/nav2_smoother/include/nav2_smoother/nav2_smoother.hpp @@ -28,9 +28,9 @@ #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp" #include "nav2_costmap_2d/footprint_subscriber.hpp" #include "nav2_msgs/action/smooth_path.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/simple_action_server.hpp" +#include "nav2_ros_common/simple_action_server.hpp" #include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_loader.hpp" @@ -42,7 +42,7 @@ namespace nav2_smoother * @brief This class hosts variety of plugins of different algorithms to * smooth or refine a path from the exposed SmoothPath action server. */ -class SmootherServer : public nav2_util::LifecycleNode +class SmootherServer : public nav2::LifecycleNode { public: using SmootherMap = std::unordered_map; @@ -68,7 +68,7 @@ class SmootherServer : public nav2_util::LifecycleNode * @throw pluginlib::PluginlibException When failed to initialize smoother * plugin */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Loads smoother plugins from parameter file @@ -84,7 +84,7 @@ class SmootherServer : public nav2_util::LifecycleNode * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivates member variables @@ -94,7 +94,7 @@ class SmootherServer : public nav2_util::LifecycleNode * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Calls clean up states and resets member variables. @@ -104,18 +104,18 @@ class SmootherServer : public nav2_util::LifecycleNode * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in Shutdown state * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; using Action = nav2_msgs::action::SmoothPath; using ActionResult = Action::Result; - using ActionServer = nav2_util::SimpleActionServer; + using ActionServer = nav2::SimpleActionServer; /** * @brief SmoothPath action server callback. Handles action server updates and @@ -144,14 +144,14 @@ class SmootherServer : public nav2_util::LifecycleNode bool validate(const nav_msgs::msg::Path & path); // Our action server implements the SmoothPath action - std::unique_ptr action_server_; + typename ActionServer::SharedPtr action_server_; // Transforms std::shared_ptr tf_; std::shared_ptr transform_listener_; // Publishers and subscribers - rclcpp_lifecycle::LifecyclePublisher::SharedPtr plan_publisher_; + nav2::Publisher::SharedPtr plan_publisher_; // Smoother Plugins pluginlib::ClassLoader lp_loader_; diff --git a/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp b/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp index 2f793011094..e18c0b823e5 100644 --- a/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp +++ b/nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp @@ -28,7 +28,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/cost_values.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav_msgs/msg/path.hpp" #include "angles/angles.h" #include "tf2/utils.hpp" @@ -54,7 +54,7 @@ class SavitzkyGolaySmoother : public nav2_core::Smoother ~SavitzkyGolaySmoother() override = default; void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string name, std::shared_ptr, std::shared_ptr, std::shared_ptr) override; diff --git a/nav2_smoother/include/nav2_smoother/simple_smoother.hpp b/nav2_smoother/include/nav2_smoother/simple_smoother.hpp index 5861f9dae0a..dfaeba953aa 100644 --- a/nav2_smoother/include/nav2_smoother/simple_smoother.hpp +++ b/nav2_smoother/include/nav2_smoother/simple_smoother.hpp @@ -28,10 +28,11 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/cost_values.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav_msgs/msg/path.hpp" #include "angles/angles.h" #include "tf2/utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_smoother { @@ -54,7 +55,7 @@ class SimpleSmoother : public nav2_core::Smoother ~SimpleSmoother() override = default; void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string name, std::shared_ptr, std::shared_ptr, std::shared_ptr) override; diff --git a/nav2_smoother/include/nav2_smoother/smoother_utils.hpp b/nav2_smoother/include/nav2_smoother/smoother_utils.hpp index c9e326c7f36..500dd7a9351 100644 --- a/nav2_smoother/include/nav2_smoother/smoother_utils.hpp +++ b/nav2_smoother/include/nav2_smoother/smoother_utils.hpp @@ -27,7 +27,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/cost_values.hpp" #include "nav2_util/geometry_utils.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav_msgs/msg/path.hpp" #include "angles/angles.h" #include "tf2/utils.hpp" diff --git a/nav2_smoother/package.xml b/nav2_smoother/package.xml index 72daaa67bd2..e7d4708d790 100644 --- a/nav2_smoother/package.xml +++ b/nav2_smoother/package.xml @@ -23,6 +23,7 @@ rclcpp_lifecycle tf2 tf2_ros + nav2_ros_common ament_cmake_gtest ament_index_cpp diff --git a/nav2_smoother/src/nav2_smoother.cpp b/nav2_smoother/src/nav2_smoother.cpp index b09b3171eb4..2c916d97e2c 100644 --- a/nav2_smoother/src/nav2_smoother.cpp +++ b/nav2_smoother/src/nav2_smoother.cpp @@ -22,7 +22,7 @@ #include "nav2_core/smoother_exceptions.hpp" #include "nav2_smoother/nav2_smoother.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav_2d_utils/conversions.hpp" #include "nav_2d_utils/tf_help.hpp" #include "tf2_ros/create_timer_ros.h" @@ -60,7 +60,7 @@ SmootherServer::~SmootherServer() smoothers_.clear(); } -nav2_util::CallbackReturn +nav2::CallbackReturn SmootherServer::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring smoother server"); @@ -70,7 +70,7 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state) get_parameter("smoother_plugins", smoother_ids_); if (smoother_ids_ == default_ids_) { for (size_t i = 0; i < default_ids_.size(); ++i) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, default_ids_[i] + ".plugin", rclcpp::ParameterValue(default_types_[i])); } @@ -99,22 +99,21 @@ SmootherServer::on_configure(const rclcpp_lifecycle::State & state) if (!loadSmootherPlugins()) { on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } // Initialize pubs & subs - plan_publisher_ = create_publisher("plan_smoothed", 1); + plan_publisher_ = create_publisher("plan_smoothed"); // Create the action server that we implement with our smoothPath method - action_server_ = std::make_unique( - shared_from_this(), + action_server_ = create_action_server( "smooth_path", std::bind(&SmootherServer::smoothPlan, this), nullptr, std::chrono::milliseconds(500), true); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool SmootherServer::loadSmootherPlugins() @@ -126,7 +125,7 @@ bool SmootherServer::loadSmootherPlugins() for (size_t i = 0; i != smoother_ids_.size(); i++) { try { smoother_types_[i] = - nav2_util::get_plugin_type_param(node, smoother_ids_[i]); + nav2::get_plugin_type_param(node, smoother_ids_[i]); nav2_core::Smoother::Ptr smoother = lp_loader_.createUniqueInstance(smoother_types_[i]); RCLCPP_INFO( @@ -155,7 +154,7 @@ bool SmootherServer::loadSmootherPlugins() return true; } -nav2_util::CallbackReturn +nav2::CallbackReturn SmootherServer::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -170,10 +169,10 @@ SmootherServer::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn SmootherServer::on_deactivate(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -188,10 +187,10 @@ SmootherServer::on_deactivate(const rclcpp_lifecycle::State &) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn SmootherServer::on_cleanup(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -212,14 +211,14 @@ SmootherServer::on_cleanup(const rclcpp_lifecycle::State &) costmap_sub_.reset(); collision_checker_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn SmootherServer::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool SmootherServer::findSmootherId( diff --git a/nav2_smoother/src/savitzky_golay_smoother.cpp b/nav2_smoother/src/savitzky_golay_smoother.cpp index 5ea1f4284cd..af23cf30995 100644 --- a/nav2_smoother/src/savitzky_golay_smoother.cpp +++ b/nav2_smoother/src/savitzky_golay_smoother.cpp @@ -23,10 +23,10 @@ namespace nav2_smoother using namespace smoother_utils; // NOLINT using namespace nav2_util::geometry_utils; // NOLINT using namespace std::chrono; // NOLINT -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; void SavitzkyGolaySmoother::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr/*tf*/, std::shared_ptr/*costmap_sub*/, std::shared_ptr/*footprint_sub*/) diff --git a/nav2_smoother/src/simple_smoother.cpp b/nav2_smoother/src/simple_smoother.cpp index 76be2eccfed..db9f323e8a1 100644 --- a/nav2_smoother/src/simple_smoother.cpp +++ b/nav2_smoother/src/simple_smoother.cpp @@ -22,10 +22,10 @@ namespace nav2_smoother using namespace smoother_utils; // NOLINT using namespace nav2_util::geometry_utils; // NOLINT using namespace std::chrono; // NOLINT -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; void SimpleSmoother::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr/*tf*/, std::shared_ptr costmap_sub, std::shared_ptr/*footprint_sub*/) diff --git a/nav2_smoother/test/CMakeLists.txt b/nav2_smoother/test/CMakeLists.txt index ce361ad9a46..99bb0388538 100644 --- a/nav2_smoother/test/CMakeLists.txt +++ b/nav2_smoother/test/CMakeLists.txt @@ -12,7 +12,13 @@ target_link_libraries(test_smoother_server rclcpp::rclcpp rclcpp_action::rclcpp_action rclcpp_lifecycle::rclcpp_lifecycle + nav2_ros_common::nav2_ros_common ) +target_include_directories(test_smoother_server + PUBLIC + "$" + "$" + "$") ament_add_gtest(test_simple_smoother test_simple_smoother.cpp @@ -28,7 +34,13 @@ target_link_libraries(test_simple_smoother rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle tf2::tf2 + nav2_ros_common::nav2_ros_common ) +target_include_directories(test_simple_smoother + PUBLIC + "$" + "$" + "$") ament_add_gtest(test_savitzky_golay_smoother test_savitzky_golay_smoother.cpp @@ -45,4 +57,10 @@ target_link_libraries(test_savitzky_golay_smoother rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common ) +target_include_directories(test_savitzky_golay_smoother + PUBLIC + "$" + "$" + "$") diff --git a/nav2_smoother/test/test_savitzky_golay_smoother.cpp b/nav2_smoother/test/test_savitzky_golay_smoother.cpp index 4ffb4520260..b31587a53f7 100644 --- a/nav2_smoother/test/test_savitzky_golay_smoother.cpp +++ b/nav2_smoother/test/test_savitzky_golay_smoother.cpp @@ -26,7 +26,7 @@ #include "nav2_costmap_2d/costmap_2d.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_msgs/msg/costmap.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smoother/savitzky_golay_smoother.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" @@ -36,8 +36,8 @@ using namespace std::chrono_literals; // NOLINT TEST(SmootherTest, test_sg_smoother_basics) { - rclcpp_lifecycle::LifecycleNode::SharedPtr node = - std::make_shared("SmacSGSmootherTest"); + nav2::LifecycleNode::SharedPtr node = + std::make_shared("SmacSGSmootherTest"); std::shared_ptr costmap_msg = std::make_shared(); @@ -48,9 +48,8 @@ TEST(SmootherTest, test_sg_smoother_basics) costmap_msg->metadata.size_x = 100; costmap_msg->metadata.size_y = 100; - std::weak_ptr parent = node; std::shared_ptr dummy_costmap; - dummy_costmap = std::make_shared(parent, "dummy_topic"); + dummy_costmap = std::make_shared(node, "dummy_topic"); dummy_costmap->costmapCallback(costmap_msg); // Make smoother @@ -58,7 +57,7 @@ TEST(SmootherTest, test_sg_smoother_basics) std::shared_ptr dummy_footprint; node->declare_parameter("test.do_refinement", rclcpp::ParameterValue(false)); auto smoother = std::make_unique(); - smoother->configure(parent, "test", dummy_tf, dummy_costmap, dummy_footprint); + smoother->configure(node, "test", dummy_tf, dummy_costmap, dummy_footprint); smoother->activate(); rclcpp::Duration max_time = rclcpp::Duration::from_seconds(1.0); // 1 seconds @@ -110,8 +109,8 @@ TEST(SmootherTest, test_sg_smoother_basics) TEST(SmootherTest, test_sg_smoother_noisey_path) { - rclcpp_lifecycle::LifecycleNode::SharedPtr node = - std::make_shared("SmacSGSmootherTest"); + nav2::LifecycleNode::SharedPtr node = + std::make_shared("SmacSGSmootherTest"); std::shared_ptr costmap_msg = std::make_shared(); @@ -122,9 +121,8 @@ TEST(SmootherTest, test_sg_smoother_noisey_path) costmap_msg->metadata.size_x = 100; costmap_msg->metadata.size_y = 100; - std::weak_ptr parent = node; std::shared_ptr dummy_costmap; - dummy_costmap = std::make_shared(parent, "dummy_topic"); + dummy_costmap = std::make_shared(node, "dummy_topic"); dummy_costmap->costmapCallback(costmap_msg); // Make smoother @@ -132,7 +130,7 @@ TEST(SmootherTest, test_sg_smoother_noisey_path) std::shared_ptr dummy_footprint; node->declare_parameter("test.do_refinement", rclcpp::ParameterValue(false)); auto smoother = std::make_unique(); - smoother->configure(parent, "test", dummy_tf, dummy_costmap, dummy_footprint); + smoother->configure(node, "test", dummy_tf, dummy_costmap, dummy_footprint); rclcpp::Duration max_time = rclcpp::Duration::from_seconds(1.0); // 1 seconds // Given nominal irregular/noisey path, test that the output is shorter and smoother @@ -193,7 +191,7 @@ TEST(SmootherTest, test_sg_smoother_noisey_path) // Test again with refinement, even shorter and smoother node->set_parameter(rclcpp::Parameter("test.do_refinement", rclcpp::ParameterValue(true))); - smoother->configure(parent, "test", dummy_tf, dummy_costmap, dummy_footprint); + smoother->configure(node, "test", dummy_tf, dummy_costmap, dummy_footprint); nav_msgs::msg::Path noisey_path_refined = noisey_path_baseline; EXPECT_TRUE(smoother->smooth(noisey_path_refined, max_time)); @@ -211,8 +209,8 @@ TEST(SmootherTest, test_sg_smoother_noisey_path) TEST(SmootherTest, test_sg_smoother_reversing) { - rclcpp_lifecycle::LifecycleNode::SharedPtr node = - std::make_shared("SmacSGSmootherTest"); + nav2::LifecycleNode::SharedPtr node = + std::make_shared("SmacSGSmootherTest"); std::shared_ptr costmap_msg = std::make_shared(); @@ -223,9 +221,8 @@ TEST(SmootherTest, test_sg_smoother_reversing) costmap_msg->metadata.size_x = 100; costmap_msg->metadata.size_y = 100; - std::weak_ptr parent = node; std::shared_ptr dummy_costmap; - dummy_costmap = std::make_shared(parent, "dummy_topic"); + dummy_costmap = std::make_shared(node, "dummy_topic"); dummy_costmap->costmapCallback(costmap_msg); // Make smoother @@ -233,7 +230,7 @@ TEST(SmootherTest, test_sg_smoother_reversing) std::shared_ptr dummy_footprint; node->declare_parameter("test.do_refinement", rclcpp::ParameterValue(false)); auto smoother = std::make_unique(); - smoother->configure(parent, "test", dummy_tf, dummy_costmap, dummy_footprint); + smoother->configure(node, "test", dummy_tf, dummy_costmap, dummy_footprint); rclcpp::Duration max_time = rclcpp::Duration::from_seconds(1.0); // 1 seconds // Test reversing / multiple segments via a cusp diff --git a/nav2_smoother/test/test_simple_smoother.cpp b/nav2_smoother/test/test_simple_smoother.cpp index 14291ac3a1f..311b9838276 100644 --- a/nav2_smoother/test/test_simple_smoother.cpp +++ b/nav2_smoother/test/test_simple_smoother.cpp @@ -20,7 +20,7 @@ #include "rclcpp/rclcpp.hpp" #include "nav2_costmap_2d/costmap_subscriber.hpp" #include "nav2_msgs/msg/costmap.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_smoother/simple_smoother.hpp" #include "nav2_core/smoother_exceptions.hpp" @@ -49,8 +49,8 @@ class SmootherWrapper : public nav2_smoother::SimpleSmoother TEST(SmootherTest, test_simple_smoother) { - rclcpp_lifecycle::LifecycleNode::SharedPtr node = - std::make_shared("SmacSmootherTest"); + nav2::LifecycleNode::SharedPtr node = + std::make_shared("SmacSmootherTest"); std::shared_ptr costmap_msg = std::make_shared(); @@ -68,16 +68,15 @@ TEST(SmootherTest, test_simple_smoother) } } - std::weak_ptr parent = node; std::shared_ptr dummy_costmap; - dummy_costmap = std::make_shared(parent, "dummy_topic"); + dummy_costmap = std::make_shared(node, "dummy_topic"); dummy_costmap->costmapCallback(costmap_msg); // Make smoother std::shared_ptr dummy_tf; std::shared_ptr dummy_footprint; auto smoother = std::make_unique(); - smoother->configure(parent, "test", dummy_tf, dummy_costmap, dummy_footprint); + smoother->configure(node, "test", dummy_tf, dummy_costmap, dummy_footprint); // Test that an irregular distributed path becomes more distributed nav_msgs::msg::Path straight_irregular_path; diff --git a/nav2_smoother/test/test_smoother_server.cpp b/nav2_smoother/test/test_smoother_server.cpp index 8fb1b6ad0df..5ebf446be3e 100644 --- a/nav2_smoother/test/test_smoother_server.cpp +++ b/nav2_smoother/test/test_smoother_server.cpp @@ -20,8 +20,7 @@ #include #include "gtest/gtest.h" -#include "rclcpp/rclcpp.hpp" - +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "nav2_core/smoother.hpp" #include "nav2_core/planner_exceptions.hpp" @@ -43,7 +42,7 @@ class DummySmoother : public nav2_core::Smoother ~DummySmoother() {} virtual void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string, std::shared_ptr, std::shared_ptr, std::shared_ptr) {} @@ -122,7 +121,7 @@ class DummyCostmapSubscriber : public nav2_costmap_2d::CostmapSubscriber { public: DummyCostmapSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::string & topic_name) : CostmapSubscriber(node, topic_name) { @@ -159,7 +158,7 @@ class DummyFootprintSubscriber : public nav2_costmap_2d::FootprintSubscriber { public: DummyFootprintSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::string & topic_name, tf2_ros::Buffer & tf) : FootprintSubscriber(node, topic_name, tf) @@ -200,11 +199,11 @@ class DummySmootherServer : public nav2_smoother::SmootherServer default_types_.resize(1, "DummySmoother"); } - nav2_util::CallbackReturn + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) { auto result = SmootherServer::on_configure(state); - if (result != nav2_util::CallbackReturn::SUCCESS) { + if (result != nav2::CallbackReturn::SUCCESS) { return result; } @@ -235,8 +234,8 @@ class SmootherTest : public ::testing::Test void SetUp() override { node_ = - std::make_shared( - "LifecycleSmootherTestNode", rclcpp::NodeOptions()); + std::make_shared( + "LifecycleSmootherTestNode"); smoother_server_ = std::make_shared(); smoother_server_->set_parameter( @@ -321,9 +320,9 @@ class SmootherTest : public ::testing::Test return future_result.get(); } - std::shared_ptr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr smoother_server_; - std::shared_ptr> client_; + std::shared_ptr> client_; std::shared_ptr> goal_handle_; }; diff --git a/nav2_system_tests/CMakeLists.txt b/nav2_system_tests/CMakeLists.txt index 14accf51e39..e2c2e03495e 100644 --- a/nav2_system_tests/CMakeLists.txt +++ b/nav2_system_tests/CMakeLists.txt @@ -31,6 +31,7 @@ if(BUILD_TESTING) find_package(std_msgs REQUIRED) find_package(tf2 REQUIRED) find_package(tf2_geometry_msgs REQUIRED) + find_package(nav2_ros_common REQUIRED) find_package(tf2_ros REQUIRED) find_package(visualization_msgs REQUIRED) @@ -49,6 +50,12 @@ if(BUILD_TESTING) pluginlib::pluginlib ) pluginlib_export_plugin_description_file(nav2_core src/error_codes/controller_plugins.xml) + target_include_directories(${local_controller_plugin_lib} + PUBLIC + "$" + "$" + "$" + ) install(TARGETS ${local_controller_plugin_lib} ARCHIVE DESTINATION lib @@ -71,6 +78,12 @@ if(BUILD_TESTING) rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros ) + target_include_directories(${global_planner_plugin_lib} + PUBLIC + "$" + "$" + "$" + ) pluginlib_export_plugin_description_file(nav2_core src/error_codes/planner_plugins.xml) install(TARGETS ${global_planner_plugin_lib} @@ -94,6 +107,12 @@ if(BUILD_TESTING) rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros ) + target_include_directories(${smoother_plugin_lib} + PUBLIC + "$" + "$" + "$" + ) pluginlib_export_plugin_description_file(nav2_core src/error_codes/smoother_plugins.xml) install(TARGETS ${smoother_plugin_lib} diff --git a/nav2_system_tests/package.xml b/nav2_system_tests/package.xml index 7a8261b63d7..c32ae6ae33b 100644 --- a/nav2_system_tests/package.xml +++ b/nav2_system_tests/package.xml @@ -42,6 +42,7 @@ tf2_geometry_msgs tf2_ros visualization_msgs + nav2_ros_common ament_cmake diff --git a/nav2_system_tests/src/behavior_tree/CMakeLists.txt b/nav2_system_tests/src/behavior_tree/CMakeLists.txt index 66d4fb1e1fb..f4054500013 100644 --- a/nav2_system_tests/src/behavior_tree/CMakeLists.txt +++ b/nav2_system_tests/src/behavior_tree/CMakeLists.txt @@ -11,4 +11,11 @@ target_link_libraries(test_behavior_tree_node nav2_util::nav2_util_core rclcpp::rclcpp tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common +) +target_include_directories(test_behavior_tree_node + PUBLIC + "$" + "$" + "$" ) diff --git a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp index 52c19fefa7b..2f62894abb7 100644 --- a/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp +++ b/nav2_system_tests/src/behavior_tree/test_behavior_tree_node.cpp @@ -32,6 +32,7 @@ #include "nav2_util/odometry_utils.hpp" #include "nav2_util/string_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_behavior_tree/plugins_list.hpp" @@ -52,7 +53,7 @@ class BehaviorTreeHandler public: BehaviorTreeHandler() { - node_ = rclcpp::Node::make_shared("behavior_tree_handler"); + node_ = std::make_shared("behavior_tree_handler"); tf_ = std::make_shared(node_->get_clock()); auto timer_interface = std::make_shared( @@ -141,7 +142,7 @@ class BehaviorTreeHandler BT::Tree tree; private: - rclcpp::Node::SharedPtr node_; + nav2::LifecycleNode::SharedPtr node_; std::shared_ptr tf_; std::shared_ptr tf_listener_; diff --git a/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt b/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt index 0bc3240cc83..2f5a0c58af7 100644 --- a/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt +++ b/nav2_system_tests/src/behaviors/assisted_teleop/CMakeLists.txt @@ -15,8 +15,14 @@ target_link_libraries(${test_assisted_teleop_behavior} ${std_msgs_TARGETS} tf2::tf2 tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common +) +target_include_directories(${test_assisted_teleop_behavior} + PUBLIC + "$" + "$" + "$" ) - ament_add_test(test_assisted_teleop_behavior GENERATE_RESULT_FOR_RETURN_CODE_ZERO COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_assisted_teleop_behavior_launch.py" diff --git a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp index ebfb1f53a64..3ffd679e930 100644 --- a/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/assisted_teleop/assisted_teleop_behavior_tester.hpp @@ -28,7 +28,7 @@ #include "geometry_msgs/msg/pose2_d.hpp" #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp" #include "nav2_msgs/action/assisted_teleop.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "nav2_util/robot_utils.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp/rclcpp.hpp" @@ -86,11 +86,11 @@ class AssistedTeleopBehaviorTester rclcpp::Publisher::SharedPtr cmd_vel_pub_; // Subscribers - rclcpp::Subscription::SharedPtr subscription_; - rclcpp::Subscription::SharedPtr filtered_vel_sub_; + nav2::Subscription::SharedPtr subscription_; + nav2::Subscription::SharedPtr filtered_vel_sub_; // Action client to call AssistedTeleop action - rclcpp_action::Client::SharedPtr client_ptr_; + nav2::ActionClient::SharedPtr client_ptr_; // collision checking std::shared_ptr costmap_sub_; diff --git a/nav2_system_tests/src/behaviors/wait/CMakeLists.txt b/nav2_system_tests/src/behaviors/wait/CMakeLists.txt index 5e2d4d656be..13e99462b46 100644 --- a/nav2_system_tests/src/behaviors/wait/CMakeLists.txt +++ b/nav2_system_tests/src/behaviors/wait/CMakeLists.txt @@ -13,6 +13,13 @@ target_link_libraries(${test_wait_behavior_exec} rclcpp_action::rclcpp_action tf2::tf2 tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common +) +target_include_directories(${test_wait_behavior_exec} + PUBLIC + "$" + "$" + "$" ) ament_add_test(test_wait_behavior diff --git a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp index cef62bdaf56..5a7313c0cd5 100644 --- a/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp +++ b/nav2_system_tests/src/behaviors/wait/wait_behavior_tester.hpp @@ -27,7 +27,8 @@ #include "rclcpp_action/rclcpp_action.hpp" #include "nav2_msgs/action/wait.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" @@ -79,10 +80,10 @@ class WaitBehaviorTester rclcpp::Publisher::SharedPtr publisher_; // Subscriber for amcl pose - rclcpp::Subscription::SharedPtr subscription_; + nav2::Subscription::SharedPtr subscription_; // Action client to call wait action - rclcpp_action::Client::SharedPtr client_ptr_; + nav2::ActionClient::SharedPtr client_ptr_; }; } // namespace nav2_system_tests diff --git a/nav2_system_tests/src/dummy_controller/CMakeLists.txt b/nav2_system_tests/src/dummy_controller/CMakeLists.txt index 688234b2a8a..c6b03837191 100644 --- a/nav2_system_tests/src/dummy_controller/CMakeLists.txt +++ b/nav2_system_tests/src/dummy_controller/CMakeLists.txt @@ -7,4 +7,11 @@ target_link_libraries(dummy_controller_node PRIVATE nav2_behavior_tree::nav2_behavior_tree nav2_util::nav2_util_core rclcpp::rclcpp + nav2_ros_common::nav2_ros_common +) +target_include_directories(dummy_controller_node + PUBLIC + "$" + "$" + "$" ) diff --git a/nav2_system_tests/src/dummy_planner/CMakeLists.txt b/nav2_system_tests/src/dummy_planner/CMakeLists.txt index 14fada8fcc6..9be653e0a4d 100644 --- a/nav2_system_tests/src/dummy_planner/CMakeLists.txt +++ b/nav2_system_tests/src/dummy_planner/CMakeLists.txt @@ -5,4 +5,11 @@ add_executable(dummy_planner_node target_link_libraries(dummy_planner_node PRIVATE nav2_behavior_tree::nav2_behavior_tree rclcpp::rclcpp + nav2_ros_common::nav2_ros_common +) +target_include_directories(dummy_planner_node + PUBLIC + "$" + "$" + "$" ) diff --git a/nav2_system_tests/src/error_codes/controller/controller_error_plugins.hpp b/nav2_system_tests/src/error_codes/controller/controller_error_plugins.hpp index ba194b195d8..cb5c626b2b8 100644 --- a/nav2_system_tests/src/error_codes/controller/controller_error_plugins.hpp +++ b/nav2_system_tests/src/error_codes/controller/controller_error_plugins.hpp @@ -31,7 +31,7 @@ class UnknownErrorController : public nav2_core::Controller ~UnknownErrorController() = default; void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string, std::shared_ptr, std::shared_ptr) override {} diff --git a/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp b/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp index 77b23aeccef..0e6b31c7af0 100644 --- a/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp +++ b/nav2_system_tests/src/error_codes/planner/planner_error_plugin.hpp @@ -25,7 +25,7 @@ #include "nav2_core/global_planner.hpp" #include "nav_msgs/msg/path.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_core/planner_exceptions.hpp" @@ -39,7 +39,7 @@ class UnknownErrorPlanner : public nav2_core::GlobalPlanner ~UnknownErrorPlanner() = default; void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string, std::shared_ptr, std::shared_ptr) override {} diff --git a/nav2_system_tests/src/error_codes/smoother/smoother_error_plugin.hpp b/nav2_system_tests/src/error_codes/smoother/smoother_error_plugin.hpp index 45ad7f469e2..3687d13cec5 100644 --- a/nav2_system_tests/src/error_codes/smoother/smoother_error_plugin.hpp +++ b/nav2_system_tests/src/error_codes/smoother/smoother_error_plugin.hpp @@ -28,7 +28,7 @@ class UnknownErrorSmoother : public nav2_core::Smoother { public: void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr &, + const nav2::LifecycleNode::WeakPtr &, std::string, std::shared_ptr, std::shared_ptr, std::shared_ptr) override {} diff --git a/nav2_system_tests/src/localization/CMakeLists.txt b/nav2_system_tests/src/localization/CMakeLists.txt index 9b5a9201419..a3c609894c5 100644 --- a/nav2_system_tests/src/localization/CMakeLists.txt +++ b/nav2_system_tests/src/localization/CMakeLists.txt @@ -4,6 +4,13 @@ ament_add_gtest_executable(test_localization_node target_link_libraries(test_localization_node ${geometry_msgs_TARGETS} rclcpp::rclcpp + nav2_ros_common::nav2_ros_common +) +target_include_directories(test_localization_node + PUBLIC + "$" + "$" + "$" ) ament_add_test(test_localization diff --git a/nav2_system_tests/src/localization/test_localization_node.cpp b/nav2_system_tests/src/localization/test_localization_node.cpp index 794abe33a8c..768fd06c449 100644 --- a/nav2_system_tests/src/localization/test_localization_node.cpp +++ b/nav2_system_tests/src/localization/test_localization_node.cpp @@ -18,6 +18,7 @@ #include "geometry_msgs/msg/pose_array.hpp" #include "geometry_msgs/msg/pose_with_covariance_stamped.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" using namespace std::chrono_literals; @@ -60,7 +61,7 @@ class TestAmclPose : public ::testing::Test pose_callback_ = true; } rclcpp::Publisher::SharedPtr initial_pose_pub_; - rclcpp::Subscription::SharedPtr subscription_; + nav2::Subscription::SharedPtr subscription_; geometry_msgs::msg::PoseWithCovarianceStamped testPose_; double amcl_pose_x; double amcl_pose_y; diff --git a/nav2_system_tests/src/planning/CMakeLists.txt b/nav2_system_tests/src/planning/CMakeLists.txt index 2a0e9137e07..0df3c439f9f 100644 --- a/nav2_system_tests/src/planning/CMakeLists.txt +++ b/nav2_system_tests/src/planning/CMakeLists.txt @@ -16,6 +16,13 @@ target_link_libraries(${test_planner_costmaps_exec} rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros ${visualization_msgs_TARGETS} + nav2_ros_common::nav2_ros_common +) +target_include_directories(${test_planner_costmaps_exec} + PUBLIC + "$" + "$" + "$" ) set(test_planner_random_exec test_planner_random_node) @@ -36,6 +43,13 @@ target_link_libraries(${test_planner_random_exec} rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros ${visualization_msgs_TARGETS} + nav2_ros_common::nav2_ros_common +) +target_include_directories(${test_planner_random_exec} + PUBLIC + "$" + "$" + "$" ) ament_add_test(test_planner_costmaps @@ -75,6 +89,13 @@ target_link_libraries(test_planner_plugins rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common +) +target_include_directories(test_planner_plugins + PUBLIC + "$" + "$" + "$" ) ament_add_gtest(test_planner_is_path_valid @@ -91,4 +112,11 @@ target_link_libraries(test_planner_is_path_valid rclcpp::rclcpp rclcpp_lifecycle::rclcpp_lifecycle tf2_ros::tf2_ros + nav2_ros_common::nav2_ros_common +) +target_include_directories(test_planner_is_path_valid + PUBLIC + "$" + "$" + "$" ) diff --git a/nav2_system_tests/src/planning/planner_tester.cpp b/nav2_system_tests/src/planning/planner_tester.cpp index eda7ce0b853..fbb60e7a2fe 100644 --- a/nav2_system_tests/src/planning/planner_tester.cpp +++ b/nav2_system_tests/src/planning/planner_tester.cpp @@ -38,7 +38,7 @@ namespace nav2_system_tests { PlannerTester::PlannerTester() -: Node("PlannerTester"), is_active_(false), +: nav2::LifecycleNode("PlannerTester"), is_active_(false), map_set_(false), costmap_set_(false), using_fake_costmap_(true), trinary_costmap_(true), track_unknown_space_(false), lethal_threshold_(100), unknown_cost_value_(-1), @@ -56,7 +56,7 @@ void PlannerTester::activate() is_active_ = true; // Launch a thread to process the messages for this node - spin_thread_ = std::make_unique(this); + spin_thread_ = std::make_unique(this); // We start with a 10x10 grid with no obstacles costmap_ = std::make_unique(this); @@ -75,7 +75,8 @@ void PlannerTester::activate() rclcpp::Parameter(std::string("expected_planner_frequency"), rclcpp::ParameterValue(-1.0))); planner_tester_->onConfigure(state); publishRobotTransform(); - map_pub_ = this->create_publisher("map", 1); + map_pub_ = this->create_publisher("map"); + map_pub_->on_activate(); path_valid_client_ = this->create_client("is_path_valid"); rclcpp::Rate r(1); r.sleep(); @@ -407,7 +408,7 @@ bool PlannerTester::isPathValid( request->path = path; request->max_cost = max_cost; request->consider_unknown_as_obstacle = consider_unknown_as_obstacle; - auto result = path_valid_client_->async_send_request(request); + auto result = path_valid_client_->async_call(request); RCLCPP_INFO(this->get_logger(), "Waiting for service complete"); if (rclcpp::spin_until_future_complete( diff --git a/nav2_system_tests/src/planning/planner_tester.hpp b/nav2_system_tests/src/planning/planner_tester.hpp index c7e450cfe6f..d878bc49f22 100644 --- a/nav2_system_tests/src/planning/planner_tester.hpp +++ b/nav2_system_tests/src/planning/planner_tester.hpp @@ -21,14 +21,14 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/action/compute_path_to_pose.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" #include "nav2_msgs/msg/costmap.hpp" #include "nav2_msgs/srv/get_costmap.hpp" #include "nav2_msgs/srv/is_path_valid.hpp" #include "nav2_util/costmap.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" #include "nav2_planner/planner_server.hpp" @@ -126,7 +126,7 @@ enum class TaskStatus : int8_t RUNNING = 3, }; -class PlannerTester : public rclcpp::Node +class PlannerTester : public nav2::LifecycleNode { public: using ComputePathToPoseCommand = geometry_msgs::msg::PoseStamped; @@ -192,10 +192,10 @@ class PlannerTester : public rclcpp::Node std::shared_ptr planner_tester_; // The is path valid client - rclcpp::Client::SharedPtr path_valid_client_; + nav2::ServiceClient::SharedPtr path_valid_client_; // A thread for spinning the ROS node - std::unique_ptr spin_thread_; + std::unique_ptr spin_thread_; // The tester must provide the robot pose through a transform std::unique_ptr base_transform_; @@ -206,7 +206,7 @@ class PlannerTester : public rclcpp::Node void updateRobotPosition(const geometry_msgs::msg::Point & position); // Occupancy grid publisher for visualization - rclcpp::Publisher::SharedPtr map_pub_; + nav2::Publisher::SharedPtr map_pub_; rclcpp::TimerBase::SharedPtr map_timer_; rclcpp::WallRate map_publish_rate_; void mapCallback(); 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 27b953efcf9..cd79acfe75a 100644 --- a/nav2_system_tests/src/planning/test_planner_costmaps_node.cpp +++ b/nav2_system_tests/src/planning/test_planner_costmaps_node.cpp @@ -18,7 +18,6 @@ #include "rclcpp/rclcpp.hpp" #include "planner_tester.hpp" -#include "nav2_util/lifecycle_utils.hpp" using namespace std::chrono_literals; diff --git a/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp b/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp index 59f1ac5a386..d8879561ef7 100644 --- a/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp +++ b/nav2_system_tests/src/planning/test_planner_is_path_valid.cpp @@ -20,7 +20,6 @@ #include "nav2_msgs/srv/is_path_valid.hpp" #include "rclcpp/rclcpp.hpp" #include "planner_tester.hpp" -#include "nav2_util/lifecycle_utils.hpp" using nav2_system_tests::PlannerTester; using nav2_util::TestCostmap; diff --git a/nav2_system_tests/src/planning/test_planner_plugins.cpp b/nav2_system_tests/src/planning/test_planner_plugins.cpp index 6762718739a..f334fc1b89d 100644 --- a/nav2_system_tests/src/planning/test_planner_plugins.cpp +++ b/nav2_system_tests/src/planning/test_planner_plugins.cpp @@ -21,7 +21,6 @@ #include "nav_msgs/msg/path.hpp" #include "rclcpp/rclcpp.hpp" #include "planner_tester.hpp" -#include "nav2_util/lifecycle_utils.hpp" #include "nav2_util/geometry_utils.hpp" #include "nav2_core/planner_exceptions.hpp" @@ -157,7 +156,7 @@ TEST(testPluginMap, Failures) obj->set_parameter(rclcpp::Parameter("expected_planner_frequency", 100000.0)); obj->onConfigure(state); obj->create_subscription( - "plan", rclcpp::SystemDefaultsQoS(), callback); + "plan", callback); geometry_msgs::msg::PoseStamped start; geometry_msgs::msg::PoseStamped goal; diff --git a/nav2_system_tests/src/updown/CMakeLists.txt b/nav2_system_tests/src/updown/CMakeLists.txt index a6260ff35e0..5fecb7d28b6 100644 --- a/nav2_system_tests/src/updown/CMakeLists.txt +++ b/nav2_system_tests/src/updown/CMakeLists.txt @@ -6,6 +6,13 @@ target_link_libraries(test_updown PRIVATE nav2_lifecycle_manager::nav2_lifecycle_manager_core rclcpp::rclcpp ) +target_include_directories(test_updown + PUBLIC + "$" + "$" + "$" +) + install(TARGETS test_updown RUNTIME DESTINATION lib/${PROJECT_NAME}) install(FILES test_updown_launch.py DESTINATION share/${PROJECT_NAME}) diff --git a/nav2_theta_star_planner/CMakeLists.txt b/nav2_theta_star_planner/CMakeLists.txt index de6778fe2ba..b5ec6623dee 100644 --- a/nav2_theta_star_planner/CMakeLists.txt +++ b/nav2_theta_star_planner/CMakeLists.txt @@ -13,6 +13,7 @@ find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(rcl_interfaces REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -25,7 +26,8 @@ add_library(${library_name} SHARED target_include_directories(${library_name} PUBLIC "$" - "$") + "$" + "$") target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} nav2_core::nav2_core @@ -88,6 +90,7 @@ ament_export_dependencies( nav_msgs rclcpp rclcpp_lifecycle + nav2_ros_common rcl_interfaces tf2_ros ) diff --git a/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp b/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp index 1c7296f3ee1..50ec643a946 100644 --- a/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp +++ b/nav2_theta_star_planner/include/nav2_theta_star_planner/theta_star_planner.hpp @@ -28,10 +28,10 @@ #include "nav2_core/planner_exceptions.hpp" #include "nav_msgs/msg/path.hpp" #include "nav2_util/robot_utils.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_costmap_2d/costmap_2d_ros.hpp" #include "nav2_costmap_2d/cost_values.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_theta_star_planner/theta_star.hpp" #include "nav2_util/geometry_utils.hpp" @@ -44,7 +44,7 @@ class ThetaStarPlanner : public nav2_core::GlobalPlanner { public: void configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) override; @@ -74,7 +74,7 @@ class ThetaStarPlanner : public nav2_core::GlobalPlanner bool use_final_approach_orientation_; // parent node weak ptr - rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node_; + nav2::LifecycleNode::WeakPtr parent_node_; std::unique_ptr planner_; diff --git a/nav2_theta_star_planner/package.xml b/nav2_theta_star_planner/package.xml index a8860994253..0279b52fe7e 100644 --- a/nav2_theta_star_planner/package.xml +++ b/nav2_theta_star_planner/package.xml @@ -21,6 +21,7 @@ rclcpp_lifecycle rcl_interfaces tf2_ros + nav2_ros_common ament_cmake_gtest ament_lint_auto diff --git a/nav2_theta_star_planner/src/theta_star_planner.cpp b/nav2_theta_star_planner/src/theta_star_planner.cpp index 202516daa9d..c0442be888d 100644 --- a/nav2_theta_star_planner/src/theta_star_planner.cpp +++ b/nav2_theta_star_planner/src/theta_star_planner.cpp @@ -25,7 +25,7 @@ namespace nav2_theta_star_planner { void ThetaStarPlanner::configure( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, std::string name, std::shared_ptr tf, std::shared_ptr costmap_ros) { @@ -39,7 +39,7 @@ void ThetaStarPlanner::configure( planner_->costmap_ = costmap_ros->getCostmap(); global_frame_ = costmap_ros->getGlobalFrameID(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name_ + ".how_many_corners", rclcpp::ParameterValue(8)); node->get_parameter(name_ + ".how_many_corners", planner_->how_many_corners_); @@ -49,25 +49,25 @@ void ThetaStarPlanner::configure( RCLCPP_WARN(logger_, "Your value for - .how_many_corners was overridden, and is now set to 8"); } - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name_ + ".allow_unknown", rclcpp::ParameterValue(true)); node->get_parameter(name_ + ".allow_unknown", planner_->allow_unknown_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name_ + ".w_euc_cost", rclcpp::ParameterValue(1.0)); node->get_parameter(name_ + ".w_euc_cost", planner_->w_euc_cost_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name_ + ".w_traversal_cost", rclcpp::ParameterValue(2.0)); node->get_parameter(name_ + ".w_traversal_cost", planner_->w_traversal_cost_); planner_->w_heuristic_cost_ = planner_->w_euc_cost_ < 1.0 ? planner_->w_euc_cost_ : 1.0; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name_ + ".terminal_checking_interval", rclcpp::ParameterValue(5000)); node->get_parameter(name_ + ".terminal_checking_interval", planner_->terminal_checking_interval_); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false)); node->get_parameter(name + ".use_final_approach_orientation", use_final_approach_orientation_); } diff --git a/nav2_theta_star_planner/test/test_theta_star.cpp b/nav2_theta_star_planner/test/test_theta_star.cpp index d0b64898c1a..e6c69541f96 100644 --- a/nav2_theta_star_planner/test/test_theta_star.cpp +++ b/nav2_theta_star_planner/test/test_theta_star.cpp @@ -139,8 +139,8 @@ TEST(ThetaStarTest, test_theta_star) { // Smoke tests meant to detect issues arising from the plugin part rather than the algorithm TEST(ThetaStarPlanner, test_theta_star_planner) { - rclcpp_lifecycle::LifecycleNode::SharedPtr life_node = - std::make_shared("ThetaStarPlannerTest"); + nav2::LifecycleNode::SharedPtr life_node = + std::make_shared("ThetaStarPlannerTest"); std::shared_ptr costmap_ros = std::make_shared("global_costmap"); @@ -184,8 +184,8 @@ TEST(ThetaStarPlanner, test_theta_star_planner) { TEST(ThetaStarPlanner, test_theta_star_reconfigure) { - rclcpp_lifecycle::LifecycleNode::SharedPtr life_node = - std::make_shared("ThetaStarPlannerTest"); + nav2::LifecycleNode::SharedPtr life_node = + std::make_shared("ThetaStarPlannerTest"); std::shared_ptr costmap_ros = std::make_shared("global_costmap"); diff --git a/nav2_util/CMakeLists.txt b/nav2_util/CMakeLists.txt index 275873fe906..08a7908f3b3 100644 --- a/nav2_util/CMakeLists.txt +++ b/nav2_util/CMakeLists.txt @@ -12,6 +12,7 @@ find_package(nav_msgs REQUIRED) find_package(rcl_interfaces REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_action REQUIRED) +find_package(nav2_ros_common REQUIRED) find_package(rclcpp_lifecycle REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2 REQUIRED) @@ -58,6 +59,7 @@ ament_export_dependencies( tf2_geometry_msgs tf2_ros pluginlib + nav2_ros_common ) ament_export_targets(${library_name}) diff --git a/nav2_util/include/nav2_util/clear_entirely_costmap_service_client.hpp b/nav2_util/include/nav2_util/clear_entirely_costmap_service_client.hpp deleted file mode 100644 index 8b401e8a595..00000000000 --- a/nav2_util/include/nav2_util/clear_entirely_costmap_service_client.hpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// -// 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_UTIL__CLEAR_ENTIRELY_COSTMAP_SERVICE_CLIENT_HPP_ -#define NAV2_UTIL__CLEAR_ENTIRELY_COSTMAP_SERVICE_CLIENT_HPP_ - -#include -#include "nav2_util/service_client.hpp" -#include "std_srvs/srv/empty.hpp" -#include "nav2_msgs/srv/clear_entire_costmap.hpp" - -namespace nav2_util -{ -/** - * @class nav2_util::ClearEntirelyCostmapServiceClient - * @brief A service client to clear costmaps entirely - */ -class ClearEntirelyCostmapServiceClient - : public nav2_util::ServiceClient -{ -public: - /** -* @brief A constructor for nav2_util::ClearEntirelyCostmapServiceClient - */ - explicit ClearEntirelyCostmapServiceClient(const std::string & service_name) - : nav2_util::ServiceClient(service_name) - { - } - - using clearEntirelyCostmapServiceRequest = - nav2_util::ServiceClient::RequestType; - using clearEntirelyCostmapServiceResponse = - nav2_util::ServiceClient::ResponseType; -}; - -} // namespace nav2_util - -#endif // NAV2_UTIL__CLEAR_ENTIRELY_COSTMAP_SERVICE_CLIENT_HPP_ diff --git a/nav2_util/include/nav2_util/costmap.hpp b/nav2_util/include/nav2_util/costmap.hpp index 0d868df6e03..4bc5eb9df73 100644 --- a/nav2_util/include/nav2_util/costmap.hpp +++ b/nav2_util/include/nav2_util/costmap.hpp @@ -18,7 +18,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/msg/costmap.hpp" #include "nav2_msgs/msg/costmap_meta_data.hpp" #include "nav_msgs/msg/occupancy_grid.hpp" @@ -55,7 +55,7 @@ class Costmap * @param unknown_cost_value Internal costmap cell value for unknown space */ Costmap( - rclcpp::Node * node, bool trinary_costmap = true, bool track_unknown_space = true, + nav2::LifecycleNode * node, bool trinary_costmap = true, bool track_unknown_space = true, int lethal_threshold = 100, int unknown_cost_value = -1); Costmap() = delete; ~Costmap(); @@ -118,7 +118,7 @@ class Costmap uint8_t interpret_value(const int8_t value) const; // Costmap isn't itself a node - rclcpp::Node * node_; + nav2::LifecycleNode * node_; // TODO(orduno): For now, only holding costs from static map nav2_msgs::msg::CostmapMetaData costmap_properties_; diff --git a/nav2_util/include/nav2_util/lifecycle_node.hpp b/nav2_util/include/nav2_util/lifecycle_node.hpp deleted file mode 100644 index 38b2ef11a0a..00000000000 --- a/nav2_util/include/nav2_util/lifecycle_node.hpp +++ /dev/null @@ -1,220 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// -// 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_UTIL__LIFECYCLE_NODE_HPP_ -#define NAV2_UTIL__LIFECYCLE_NODE_HPP_ - -#include -#include -#include - -#include "rcl_interfaces/msg/parameter_descriptor.hpp" -#include "nav2_util/node_thread.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "rclcpp/rclcpp.hpp" -#include "bondcpp/bond.hpp" -#include "bond/msg/constants.hpp" - -namespace nav2_util -{ - -using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; - -/** - * @class nav2_util::LifecycleNode - * @brief A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters - */ -class LifecycleNode : public rclcpp_lifecycle::LifecycleNode -{ -public: - /** - * @brief A lifecycle node constructor - * @param node_name Name for the node - * @param namespace Namespace for the node, if any - * @param options Node options - */ - LifecycleNode( - const std::string & node_name, - const std::string & ns = "", - const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); - virtual ~LifecycleNode(); - - typedef struct - { - double from_value; - double to_value; - double step; - } floating_point_range; - - typedef struct - { - int from_value; - int to_value; - int step; - } integer_range; - - /** - * @brief Declare a parameter that has no integer or floating point range constraints - * @param node_name Name of parameter - * @param default_value Default node value to add - * @param description Node description - * @param additional_constraints Any additional constraints on the parameters to list - * @param read_only Whether this param should be considered read only - */ - void add_parameter( - const std::string & name, const rclcpp::ParameterValue & default_value, - const std::string & description = "", const std::string & additional_constraints = "", - bool read_only = false) - { - auto descriptor = rcl_interfaces::msg::ParameterDescriptor(); - - descriptor.name = name; - descriptor.description = description; - descriptor.additional_constraints = additional_constraints; - descriptor.read_only = read_only; - - declare_parameter(descriptor.name, default_value, descriptor); - } - - /** - * @brief Declare a parameter that has a floating point range constraint - * @param node_name Name of parameter - * @param default_value Default node value to add - * @param fp_range floating point range - * @param description Node description - * @param additional_constraints Any additional constraints on the parameters to list - * @param read_only Whether this param should be considered read only - */ - void add_parameter( - const std::string & name, const rclcpp::ParameterValue & default_value, - const floating_point_range fp_range, - const std::string & description = "", const std::string & additional_constraints = "", - bool read_only = false) - { - auto descriptor = rcl_interfaces::msg::ParameterDescriptor(); - - descriptor.name = name; - descriptor.description = description; - descriptor.additional_constraints = additional_constraints; - descriptor.read_only = read_only; - descriptor.floating_point_range.resize(1); - descriptor.floating_point_range[0].from_value = fp_range.from_value; - descriptor.floating_point_range[0].to_value = fp_range.to_value; - descriptor.floating_point_range[0].step = fp_range.step; - - declare_parameter(descriptor.name, default_value, descriptor); - } - - /** - * @brief Declare a parameter that has an integer range constraint - * @param node_name Name of parameter - * @param default_value Default node value to add - * @param integer_range Integer range - * @param description Node description - * @param additional_constraints Any additional constraints on the parameters to list - * @param read_only Whether this param should be considered read only - */ - void add_parameter( - const std::string & name, const rclcpp::ParameterValue & default_value, - const integer_range int_range, - const std::string & description = "", const std::string & additional_constraints = "", - bool read_only = false) - { - auto descriptor = rcl_interfaces::msg::ParameterDescriptor(); - - descriptor.name = name; - descriptor.description = description; - descriptor.additional_constraints = additional_constraints; - descriptor.read_only = read_only; - descriptor.integer_range.resize(1); - descriptor.integer_range[0].from_value = int_range.from_value; - descriptor.integer_range[0].to_value = int_range.to_value; - descriptor.integer_range[0].step = int_range.step; - - declare_parameter(descriptor.name, default_value, descriptor); - } - - /** - * @brief Get a shared pointer of this - */ - std::shared_ptr shared_from_this() - { - return std::static_pointer_cast( - rclcpp_lifecycle::LifecycleNode::shared_from_this()); - } - - /** - * @brief Abstracted on_error state transition callback, since unimplemented as of 2020 - * in the managed ROS2 node state machine - * @param state State prior to error transition - * @return Return type for success or failed transition to error state - */ - nav2_util::CallbackReturn on_error(const rclcpp_lifecycle::State & /*state*/) - { - RCLCPP_FATAL( - get_logger(), - "Lifecycle node %s does not have error state implemented", get_name()); - return nav2_util::CallbackReturn::SUCCESS; - } - - /** - * @brief Automatically configure and active the node - */ - void autostart(); - - /** - * @brief Perform preshutdown activities before our Context is shutdown. - * Note that this is related to our Context's shutdown sequence, not the - * lifecycle node state machine. - */ - virtual void on_rcl_preshutdown(); - - /** - * @brief Create bond connection to lifecycle manager - */ - void createBond(); - - /** - * @brief Destroy bond connection to lifecycle manager - */ - void destroyBond(); - -protected: - /** - * @brief Print notifications for lifecycle node - */ - void printLifecycleNodeNotification(); - - /** - * Register our preshutdown callback for this Node's rcl Context. - * The callback fires before this Node's Context is shutdown. - * Note this is not directly related to the lifecycle state machine. - */ - void register_rcl_preshutdown_callback(); - std::unique_ptr rcl_preshutdown_cb_handle_{nullptr}; - - /** - * Run some common cleanup steps shared between rcl preshutdown and destruction. - */ - void runCleanups(); - - // Connection to tell that server is still up - std::unique_ptr bond_{nullptr}; - double bond_heartbeat_period; - rclcpp::TimerBase::SharedPtr autostart_timer_; -}; - -} // namespace nav2_util - -#endif // NAV2_UTIL__LIFECYCLE_NODE_HPP_ diff --git a/nav2_util/include/nav2_util/lifecycle_service_client.hpp b/nav2_util/include/nav2_util/lifecycle_service_client.hpp index 341a7706b3f..64860f47e87 100644 --- a/nav2_util/include/nav2_util/lifecycle_service_client.hpp +++ b/nav2_util/include/nav2_util/lifecycle_service_client.hpp @@ -21,22 +21,41 @@ #include "lifecycle_msgs/srv/change_state.hpp" #include "lifecycle_msgs/srv/get_state.hpp" -#include "nav2_util/service_client.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/service_client.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_util { +using namespace std::chrono_literals; // NOLINT + /// Helper functions to interact with a lifecycle node. class LifecycleServiceClient { public: explicit LifecycleServiceClient( const std::string & lifecycle_node_name); + + template + explicit LifecycleServiceClient( - const std::string & lifecycle_node_name, - rclcpp::Node::SharedPtr parent_node); + const string & lifecycle_node_name, + NodeT parent_node) + : change_state_(lifecycle_node_name + "/change_state", parent_node, + true /*creates and spins an internal executor*/), + get_state_(lifecycle_node_name + "/get_state", parent_node, + true /*creates and spins an internal executor*/) + { + // Block until server is up + rclcpp::Rate r(20); + while (!get_state_.wait_for_service(2s)) { + RCLCPP_INFO( + parent_node->get_logger(), + "Waiting for service %s...", get_state_.getServiceName().c_str()); + r.sleep(); + } + } /// Trigger a state change /** @@ -54,9 +73,9 @@ class LifecycleServiceClient uint8_t get_state(const std::chrono::milliseconds timeout = std::chrono::milliseconds(2000)); protected: - rclcpp::Node::SharedPtr node_; - ServiceClient change_state_; - ServiceClient get_state_; + rclcpp::Node::SharedPtr node_; // Node only used if parent_node is not provided + nav2::ServiceClient change_state_; + nav2::ServiceClient get_state_; }; } // namespace nav2_util diff --git a/nav2_util/include/nav2_util/lifecycle_utils.hpp b/nav2_util/include/nav2_util/lifecycle_utils.hpp deleted file mode 100644 index a270aa4e7ed..00000000000 --- a/nav2_util/include/nav2_util/lifecycle_utils.hpp +++ /dev/null @@ -1,82 +0,0 @@ -// Copyright (c) 2018 Intel Corporation -// -// 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_UTIL__LIFECYCLE_UTILS_HPP_ -#define NAV2_UTIL__LIFECYCLE_UTILS_HPP_ - -#include -#include -#include -#include "nav2_util/string_utils.hpp" - -namespace nav2_util -{ - -/// Transition the given lifecycle nodes to the ACTIVATED state in order -/** At this time, service calls frequently hang for unknown reasons. The only - * way to combat that is to timeout the service call and retry it. To use this - * function, estimate how long your nodes should take to at each transition and - * set your timeout accordingly. - * \param[in] node_names A vector of the fully qualified node names to startup. - * \param[in] service_call_timeout The maximum amount of time to wait for a - * service call. - * \param[in] retries The number of times to try a state transition service call - */ -void startup_lifecycle_nodes( - const std::vector & node_names, - const std::chrono::seconds service_call_timeout = std::chrono::seconds::max(), - const int retries = 3); - -/// Transition the given lifecycle nodes to the ACTIVATED state in order. -/** - * \param[in] nodes A ':' separated list of node names. eg. "/node1:/node2" - */ -void startup_lifecycle_nodes( - const std::string & nodes, - const std::chrono::seconds service_call_timeout = std::chrono::seconds::max(), - const int retries = 3) -{ - startup_lifecycle_nodes(split(nodes, ':'), service_call_timeout, retries); -} - -/// Transition the given lifecycle nodes to the UNCONFIGURED state in order -/** At this time, service calls frequently hang for unknown reasons. The only - * way to combat that is to timeout the service call and retry it. To use this - * function, estimate how long your nodes should take to at each transition and - * set your timeout accordingly. - * \param[in] node_names A vector of the fully qualified node names to reset. - * \param[in] service_call_timeout The maximum amount of time to wait for a - * service call. - * \param[in] retries The number of times to try a state transition service call - */ -void reset_lifecycle_nodes( - const std::vector & node_names, - const std::chrono::seconds service_call_timeout = std::chrono::seconds::max(), - const int retries = 3); - -/// Transition the given lifecycle nodes to the UNCONFIGURED state in order. -/** - * \param[in] nodes A ':' separated list of node names. eg. "/node1:/node2" - */ -void reset_lifecycle_nodes( - const std::string & nodes, - const std::chrono::seconds service_call_timeout = std::chrono::seconds::max(), - const int retries = 3) -{ - reset_lifecycle_nodes(split(nodes, ':'), service_call_timeout, retries); -} - -} // namespace nav2_util - -#endif // NAV2_UTIL__LIFECYCLE_UTILS_HPP_ diff --git a/nav2_util/include/nav2_util/odometry_utils.hpp b/nav2_util/include/nav2_util/odometry_utils.hpp index 8f184b1ae36..2c34a67eebc 100644 --- a/nav2_util/include/nav2_util/odometry_utils.hpp +++ b/nav2_util/include/nav2_util/odometry_utils.hpp @@ -26,9 +26,9 @@ #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/twist_stamped.hpp" #include "nav_msgs/msg/odometry.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_util { @@ -41,17 +41,6 @@ namespace nav2_util class OdomSmoother { public: - /** - * @brief Constructor that subscribes to an Odometry topic - * @param parent NodeHandle for creating subscriber - * @param filter_duration Duration for odom history (seconds) - * @param odom_topic Topic on which odometry should be received - */ - explicit OdomSmoother( - const rclcpp::Node::WeakPtr & parent, - double filter_duration = 0.3, - const std::string & odom_topic = "odom"); - /** * @brief Overloadded Constructor for nav_util::LifecycleNode parent * that subscribes to an Odometry topic @@ -59,10 +48,26 @@ class OdomSmoother * @param filter_duration Duration for odom history (seconds) * @param odom_topic Topic on which odometry should be received */ + template explicit OdomSmoother( - const nav2_util::LifecycleNode::WeakPtr & parent, + const NodeT & parent, double filter_duration = 0.3, - const std::string & odom_topic = "odom"); + const std::string & odom_topic = "odom") + : odom_history_duration_(rclcpp::Duration::from_seconds(filter_duration)) + { + // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the + // subscription to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode + odom_sub_ = nav2::interfaces::create_subscription( + parent, odom_topic, + std::bind(&OdomSmoother::odomCallback, this, std::placeholders::_1)); + + odom_cumulate_.twist.twist.linear.x = 0; + odom_cumulate_.twist.twist.linear.y = 0; + odom_cumulate_.twist.twist.linear.z = 0; + odom_cumulate_.twist.twist.angular.x = 0; + odom_cumulate_.twist.twist.angular.y = 0; + odom_cumulate_.twist.twist.angular.z = 0; + } /** * @brief Get twist msg from smoother @@ -142,8 +147,8 @@ class OdomSmoother */ void updateState(); - bool received_odom_; - rclcpp::Subscription::SharedPtr odom_sub_; + bool received_odom_{false}; + nav2::Subscription::SharedPtr odom_sub_; nav_msgs::msg::Odometry odom_cumulate_; geometry_msgs::msg::TwistStamped vel_smooth_; std::mutex odom_mutex_; diff --git a/nav2_util/include/nav2_util/string_utils.hpp b/nav2_util/include/nav2_util/string_utils.hpp index 06d93b82a26..48decd3442b 100644 --- a/nav2_util/include/nav2_util/string_utils.hpp +++ b/nav2_util/include/nav2_util/string_utils.hpp @@ -23,13 +23,6 @@ namespace nav2_util typedef std::vector Tokens; -/* - * @brief Remove leading slash from a topic name - * @param in String of topic in - * @return String out without slash -*/ -std::string strip_leading_slash(const std::string & in); - /// /* * @brief Split a string at the delimiters diff --git a/nav2_util/include/nav2_util/twist_publisher.hpp b/nav2_util/include/nav2_util/twist_publisher.hpp index 025f3aabe68..4ba07f59ebe 100644 --- a/nav2_util/include/nav2_util/twist_publisher.hpp +++ b/nav2_util/include/nav2_util/twist_publisher.hpp @@ -28,8 +28,8 @@ #include "rclcpp/qos.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" -#include "lifecycle_node.hpp" -#include "node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" namespace nav2_util { @@ -53,12 +53,12 @@ class TwistPublisher * @param qos publisher quality of service */ explicit TwistPublisher( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::string & topic, - const rclcpp::QoS & qos) + const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS()) : topic_(topic) { - using nav2_util::declare_parameter_if_not_declared; + using nav2::declare_parameter_if_not_declared; declare_parameter_if_not_declared( node, "enable_stamped_cmd_vel", rclcpp::ParameterValue{true}); @@ -123,8 +123,8 @@ class TwistPublisher protected: std::string topic_; bool is_stamped_{true}; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr twist_pub_; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr + nav2::Publisher::SharedPtr twist_pub_; + nav2::Publisher::SharedPtr twist_stamped_pub_; }; diff --git a/nav2_util/include/nav2_util/twist_subscriber.hpp b/nav2_util/include/nav2_util/twist_subscriber.hpp index eec5a3e1ae4..92a7b55bb7e 100644 --- a/nav2_util/include/nav2_util/twist_subscriber.hpp +++ b/nav2_util/include/nav2_util/twist_subscriber.hpp @@ -28,8 +28,8 @@ #include "rclcpp/qos.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" -#include "lifecycle_node.hpp" -#include "node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_util { @@ -83,27 +83,27 @@ class TwistSubscriber typename TwistStampedCallbackT > explicit TwistSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::string & topic, - const rclcpp::QoS & qos, TwistCallbackT && TwistCallback, - TwistStampedCallbackT && TwistStampedCallback + TwistStampedCallbackT && TwistStampedCallback, + const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS() ) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "enable_stamped_cmd_vel", rclcpp::ParameterValue(true)); node->get_parameter("enable_stamped_cmd_vel", is_stamped_); if (is_stamped_) { twist_stamped_sub_ = node->create_subscription( topic, - qos, - std::forward(TwistStampedCallback)); + std::forward(TwistStampedCallback), + qos); } else { twist_sub_ = node->create_subscription( topic, - qos, - std::forward(TwistCallback)); + std::forward(TwistCallback), + qos); } } @@ -117,21 +117,21 @@ class TwistSubscriber */ template explicit TwistSubscriber( - nav2_util::LifecycleNode::SharedPtr node, + nav2::LifecycleNode::SharedPtr node, const std::string & topic, - const rclcpp::QoS & qos, - TwistStampedCallbackT && TwistStampedCallback + TwistStampedCallbackT && TwistStampedCallback, + const rclcpp::QoS & qos = nav2::qos::StandardTopicQoS() ) { - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, "enable_stamped_cmd_vel", rclcpp::ParameterValue(true)); node->get_parameter("enable_stamped_cmd_vel", is_stamped_); if (is_stamped_) { twist_stamped_sub_ = node->create_subscription( topic, - qos, - std::forward(TwistStampedCallback)); + std::forward(TwistStampedCallback), + qos); } else { throw std::invalid_argument( "enable_stamped_cmd_vel must be true when using this constructor!"); @@ -142,9 +142,9 @@ class TwistSubscriber //! @brief The user-configured value for ROS parameter enable_stamped_cmd_vel bool is_stamped_{true}; //! @brief The subscription when using Twist - rclcpp::Subscription::SharedPtr twist_sub_ {nullptr}; + nav2::Subscription::SharedPtr twist_sub_ {nullptr}; //! @brief The subscription when using TwistStamped - rclcpp::Subscription::SharedPtr twist_stamped_sub_ {nullptr}; + nav2::Subscription::SharedPtr twist_stamped_sub_ {nullptr}; }; diff --git a/nav2_util/package.xml b/nav2_util/package.xml index 97583144f86..0acd0f1a37b 100644 --- a/nav2_util/package.xml +++ b/nav2_util/package.xml @@ -30,12 +30,11 @@ tf2_msgs tf2_ros pluginlib + nav2_ros_common ament_lint_common ament_lint_auto ament_cmake_gtest - std_srvs - test_msgs ament_cmake_pytest diff --git a/nav2_util/src/CMakeLists.txt b/nav2_util/src/CMakeLists.txt index 41261f512a5..66ef54f0322 100644 --- a/nav2_util/src/CMakeLists.txt +++ b/nav2_util/src/CMakeLists.txt @@ -1,12 +1,8 @@ add_library(${library_name} SHARED costmap.cpp - node_utils.cpp lifecycle_service_client.cpp string_utils.cpp - lifecycle_utils.cpp - lifecycle_node.cpp robot_utils.cpp - node_thread.cpp odometry_utils.cpp array_parser.cpp ) @@ -32,6 +28,10 @@ target_link_libraries(${library_name} PUBLIC target_link_libraries(${library_name} PRIVATE ${bond_TARGETS} ) +target_include_directories(${library_name} PUBLIC + "$" + "$" +) add_executable(lifecycle_bringup lifecycle_bringup_commandline.cpp diff --git a/nav2_util/src/costmap.cpp b/nav2_util/src/costmap.cpp index 5ab609634b8..01eb8713628 100644 --- a/nav2_util/src/costmap.cpp +++ b/nav2_util/src/costmap.cpp @@ -32,7 +32,7 @@ const Costmap::CostValue Costmap::free_space = 0; // TODO(orduno): Port ROS1 Costmap package Costmap::Costmap( - rclcpp::Node * node, bool trinary_costmap, bool track_unknown_space, + nav2::LifecycleNode * node, bool trinary_costmap, bool track_unknown_space, int lethal_threshold, int unknown_cost_value) : node_(node), trinary_costmap_(trinary_costmap), track_unknown_space_(track_unknown_space), lethal_threshold_(lethal_threshold), unknown_cost_value_(unknown_cost_value) diff --git a/nav2_util/src/lifecycle_bringup_commandline.cpp b/nav2_util/src/lifecycle_bringup_commandline.cpp index f898898611c..b491b8bf3e6 100644 --- a/nav2_util/src/lifecycle_bringup_commandline.cpp +++ b/nav2_util/src/lifecycle_bringup_commandline.cpp @@ -18,10 +18,11 @@ #include #include #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_utils.hpp" +#include "nav2_util/lifecycle_service_client.hpp" using std::cerr; -using namespace std::chrono_literals; +using namespace std::chrono_literals; // NOLINT +using namespace nav2_util; // NOLINT void usage() { @@ -34,13 +35,57 @@ void usage() std::exit(1); } +#define RETRY(fn, retries) \ + { \ + int count = 0; \ + while (true) { \ + try { \ + fn; \ + break; \ + } catch (const std::runtime_error & e) { \ + ++count; \ + if (count > (retries)) { \ + throw e;} \ + } \ + } \ + } + +inline void startupLifecycleNode( + const std::string & node_name, + const std::chrono::seconds service_call_timeout, + const int retries) +{ + LifecycleServiceClient sc(node_name); + + // Despite waiting for the service to be available and using reliable transport + // service calls still frequently hang. To get reliable startup it's necessary + // to timeout the service call and retry it when that happens. + RETRY( + sc.change_state(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE, service_call_timeout), + retries); + RETRY( + sc.change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE, service_call_timeout), + retries); +} + +inline void startup_lifecycle_nodes( + const std::vector & node_names, + const std::chrono::seconds service_call_timeout, + const int retries = 3) +{ + for (const auto & node_name : node_names) { + startupLifecycleNode(node_name, service_call_timeout, retries); + } +} + + int main(int argc, char * argv[]) { if (argc == 1) { usage(); } rclcpp::init(0, nullptr); - nav2_util::startup_lifecycle_nodes( + startup_lifecycle_nodes( std::vector(argv + 1, argv + argc), 10s); rclcpp::shutdown(); diff --git a/nav2_util/src/lifecycle_node.cpp b/nav2_util/src/lifecycle_node.cpp deleted file mode 100644 index 3bc9dba1574..00000000000 --- a/nav2_util/src/lifecycle_node.cpp +++ /dev/null @@ -1,166 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// -// 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 "nav2_util/lifecycle_node.hpp" - -#include -#include -#include - -#include "lifecycle_msgs/msg/state.hpp" -#include "nav2_util/node_utils.hpp" - -using namespace std::chrono_literals; - -namespace nav2_util -{ - -LifecycleNode::LifecycleNode( - const std::string & node_name, - const std::string & ns, - const rclcpp::NodeOptions & options) -: rclcpp_lifecycle::LifecycleNode(node_name, ns, options) -{ - // server side never times out from lifecycle manager - this->declare_parameter(bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true); - this->set_parameter( - rclcpp::Parameter( - bond::msg::Constants::DISABLE_HEARTBEAT_TIMEOUT_PARAM, true)); - - nav2_util::declare_parameter_if_not_declared( - this, "bond_heartbeat_period", rclcpp::ParameterValue(0.1)); - this->get_parameter("bond_heartbeat_period", bond_heartbeat_period); - - bool autostart_node = false; - nav2_util::declare_parameter_if_not_declared( - this, "autostart_node", rclcpp::ParameterValue(false)); - this->get_parameter("autostart_node", autostart_node); - if (autostart_node) { - autostart(); - } - - printLifecycleNodeNotification(); - - register_rcl_preshutdown_callback(); -} - -LifecycleNode::~LifecycleNode() -{ - RCLCPP_INFO(get_logger(), "Destroying"); - - runCleanups(); - - if (rcl_preshutdown_cb_handle_) { - rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context(); - context->remove_pre_shutdown_callback(*(rcl_preshutdown_cb_handle_.get())); - rcl_preshutdown_cb_handle_.reset(); - } -} - -void LifecycleNode::createBond() -{ - if (bond_heartbeat_period > 0.0) { - RCLCPP_INFO(get_logger(), "Creating bond (%s) to lifecycle manager.", this->get_name()); - - bond_ = std::make_unique( - std::string("bond"), - this->get_name(), - shared_from_this()); - - bond_->setHeartbeatPeriod(bond_heartbeat_period); - bond_->setHeartbeatTimeout(4.0); - bond_->start(); - } -} - -void LifecycleNode::autostart() -{ - using lifecycle_msgs::msg::State; - autostart_timer_ = this->create_wall_timer( - 0s, - [this]() -> void { - autostart_timer_->cancel(); - RCLCPP_INFO(get_logger(), "Auto-starting node: %s", this->get_name()); - if (configure().id() != State::PRIMARY_STATE_INACTIVE) { - RCLCPP_ERROR(get_logger(), "Auto-starting node %s failed to configure!", this->get_name()); - return; - } - if (activate().id() != State::PRIMARY_STATE_ACTIVE) { - RCLCPP_ERROR(get_logger(), "Auto-starting node %s failed to activate!", this->get_name()); - } - }); -} - -void LifecycleNode::runCleanups() -{ - /* - * In case this lifecycle node wasn't properly shut down, do it here. - * We will give the user some ability to clean up properly here, but it's - * best effort; i.e. we aren't trying to account for all possible states. - */ - if (get_current_state().id() == - lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) - { - this->deactivate(); - } - - if (get_current_state().id() == - lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) - { - this->cleanup(); - } -} - -void LifecycleNode::on_rcl_preshutdown() -{ - RCLCPP_INFO( - get_logger(), "Running Nav2 LifecycleNode rcl preshutdown (%s)", - this->get_name()); - - runCleanups(); - - destroyBond(); -} - -void LifecycleNode::register_rcl_preshutdown_callback() -{ - rclcpp::Context::SharedPtr context = get_node_base_interface()->get_context(); - - rcl_preshutdown_cb_handle_ = std::make_unique( - context->add_pre_shutdown_callback( - std::bind(&LifecycleNode::on_rcl_preshutdown, this)) - ); -} - -void LifecycleNode::destroyBond() -{ - if (bond_heartbeat_period > 0.0) { - RCLCPP_INFO(get_logger(), "Destroying bond (%s) to lifecycle manager.", this->get_name()); - - if (bond_) { - bond_.reset(); - } - } -} - -void LifecycleNode::printLifecycleNodeNotification() -{ - RCLCPP_INFO( - get_logger(), - "\n\t%s lifecycle node launched. \n" - "\tWaiting on external lifecycle transitions to activate\n" - "\tSee https://design.ros2.org/articles/node_lifecycle.html for more information.", get_name()); -} - -} // namespace nav2_util diff --git a/nav2_util/src/lifecycle_service_client.cpp b/nav2_util/src/lifecycle_service_client.cpp index 4ff638cf2d4..d64c1a3d5da 100644 --- a/nav2_util/src/lifecycle_service_client.cpp +++ b/nav2_util/src/lifecycle_service_client.cpp @@ -21,7 +21,7 @@ #include "lifecycle_msgs/srv/change_state.hpp" #include "lifecycle_msgs/srv/get_state.hpp" -using nav2_util::generate_internal_node; +using nav2::generate_internal_node; using std::chrono::milliseconds; using std::make_shared; using std::string; @@ -47,24 +47,6 @@ LifecycleServiceClient::LifecycleServiceClient( } } -LifecycleServiceClient::LifecycleServiceClient( - const string & lifecycle_node_name, - rclcpp::Node::SharedPtr parent_node) -: node_(parent_node), - change_state_(lifecycle_node_name + "/change_state", node_, - true /*creates and spins an internal executor*/), - get_state_(lifecycle_node_name + "/get_state", node_, - true /*creates and spins an internal executor*/) -{ - // Block until server is up - rclcpp::Rate r(20); - while (!get_state_.wait_for_service(2s)) { - RCLCPP_INFO( - node_->get_logger(), "Waiting for service %s...", get_state_.getServiceName().c_str()); - r.sleep(); - } -} - bool LifecycleServiceClient::change_state( const uint8_t transition, const milliseconds transition_timeout, diff --git a/nav2_util/src/lifecycle_utils.cpp b/nav2_util/src/lifecycle_utils.cpp deleted file mode 100644 index e84bbbc55b7..00000000000 --- a/nav2_util/src/lifecycle_utils.cpp +++ /dev/null @@ -1,98 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// -// 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 -#include -#include -#include - -#include "lifecycle_msgs/msg/transition.hpp" - -#include "nav2_util/lifecycle_service_client.hpp" - -namespace nav2_util -{ - -#define RETRY(fn, retries) \ - { \ - int count = 0; \ - while (true) { \ - try { \ - fn; \ - break; \ - } catch (const std::runtime_error & e) { \ - ++count; \ - if (count > (retries)) { \ - throw e;} \ - } \ - } \ - } - -static void startupLifecycleNode( - const std::string & node_name, - const std::chrono::seconds service_call_timeout, - const int retries) -{ - LifecycleServiceClient sc(node_name); - - // Despite waiting for the service to be available and using reliable transport - // service calls still frequently hang. To get reliable startup it's necessary - // to timeout the service call and retry it when that happens. - RETRY( - sc.change_state(lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE, service_call_timeout), - retries); - RETRY( - sc.change_state(lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE, service_call_timeout), - retries); -} - -void startup_lifecycle_nodes( - const std::vector & node_names, - const std::chrono::seconds service_call_timeout, - const int retries) -{ - for (const auto & node_name : node_names) { - startupLifecycleNode(node_name, service_call_timeout, retries); - } -} - -static void resetLifecycleNode( - const std::string & node_name, - const std::chrono::seconds service_call_timeout, - const int retries) -{ - LifecycleServiceClient sc(node_name); - - // Despite waiting for the service to be available and using reliable transport - // service calls still frequently hang. To get reliable reset it's necessary - // to timeout the service call and retry it when that happens. - RETRY( - sc.change_state(lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE, service_call_timeout), - retries); - RETRY( - sc.change_state(lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP, service_call_timeout), - retries); -} - -void reset_lifecycle_nodes( - const std::vector & node_names, - const std::chrono::seconds service_call_timeout, - const int retries) -{ - for (const auto & node_name : node_names) { - resetLifecycleNode(node_name, service_call_timeout, retries); - } -} - -} // namespace nav2_util diff --git a/nav2_util/src/node_thread.cpp b/nav2_util/src/node_thread.cpp deleted file mode 100644 index adcbe50b780..00000000000 --- a/nav2_util/src/node_thread.cpp +++ /dev/null @@ -1,50 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// -// 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 -#include "nav2_util/node_thread.hpp" - -namespace nav2_util -{ - -NodeThread::NodeThread( - rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base) -: node_(node_base) -{ - executor_ = std::make_shared(); - thread_ = std::make_unique( - [&]() - { - executor_->add_node(node_); - executor_->spin(); - executor_->remove_node(node_); - }); -} - -NodeThread::NodeThread(rclcpp::executors::SingleThreadedExecutor::SharedPtr executor) -: executor_(executor) -{ - thread_ = std::make_unique( - [&]() { - executor_->spin(); - }); -} - -NodeThread::~NodeThread() -{ - executor_->cancel(); - thread_->join(); -} - -} // namespace nav2_util diff --git a/nav2_util/src/node_utils.cpp b/nav2_util/src/node_utils.cpp deleted file mode 100644 index 993eaf53b6e..00000000000 --- a/nav2_util/src/node_utils.cpp +++ /dev/null @@ -1,106 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// Copyright (c) 2023 Open Navigation LLC -// -// 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 "nav2_util/node_utils.hpp" -#include -#include -#include -#include - -using std::chrono::high_resolution_clock; -using std::to_string; -using std::string; -using std::replace_if; -using std::isalnum; - -namespace nav2_util -{ - -string sanitize_node_name(const string & potential_node_name) -{ - string node_name(potential_node_name); - // read this as `replace` characters in `node_name` `if` not alphanumeric. - // replace with '_' - replace_if( - begin(node_name), end(node_name), - [](auto c) {return !isalnum(c);}, - '_'); - return node_name; -} - -string add_namespaces(const string & top_ns, const string & sub_ns) -{ - if (!top_ns.empty() && top_ns.back() == '/') { - if (top_ns.front() == '/') { - return top_ns + sub_ns; - } else { - return "/" + top_ns + sub_ns; - } - } - - return top_ns + "/" + sub_ns; -} - -std::string time_to_string(size_t len) -{ - string output(len, '0'); // prefill the string with zeros - auto timepoint = high_resolution_clock::now(); - auto timecount = timepoint.time_since_epoch().count(); - auto timestring = to_string(timecount); - if (timestring.length() >= len) { - // if `timestring` is shorter, put it at the end of `output` - output.replace( - 0, len, - timestring, - timestring.length() - len, len); - } else { - // if `output` is shorter, just copy in the end of `timestring` - output.replace( - len - timestring.length(), timestring.length(), - timestring, - 0, timestring.length()); - } - return output; -} - -std::string generate_internal_node_name(const std::string & prefix) -{ - return sanitize_node_name(prefix) + "_" + time_to_string(8); -} - -rclcpp::Node::SharedPtr generate_internal_node(const std::string & prefix) -{ - auto options = - rclcpp::NodeOptions() - .start_parameter_services(false) - .start_parameter_event_publisher(false) - .arguments({"--ros-args", "-r", "__node:=" + generate_internal_node_name(prefix), "--"}); - return rclcpp::Node::make_shared("_", options); -} - -void setSoftRealTimePriority() -{ - sched_param sch; - sch.sched_priority = 49; - if (sched_setscheduler(0, SCHED_FIFO, &sch) == -1) { - std::string errmsg( - "Cannot set as real-time thread. Users must set: hard rtprio 99 and " - " soft rtprio 99 in /etc/security/limits.conf to enable " - "realtime prioritization! Error: "); - throw std::runtime_error(errmsg + std::strerror(errno)); - } -} - -} // namespace nav2_util diff --git a/nav2_util/src/odometry_utils.cpp b/nav2_util/src/odometry_utils.cpp index 6b50c332bcc..545b61c27a7 100644 --- a/nav2_util/src/odometry_utils.cpp +++ b/nav2_util/src/odometry_utils.cpp @@ -23,46 +23,6 @@ using namespace std::chrono_literals; // NOLINT namespace nav2_util { -OdomSmoother::OdomSmoother( - const rclcpp::Node::WeakPtr & parent, - double filter_duration, - const std::string & odom_topic) -: received_odom_(false), odom_history_duration_(rclcpp::Duration::from_seconds(filter_duration)) -{ - auto node = parent.lock(); - odom_sub_ = node->create_subscription( - odom_topic, - rclcpp::SystemDefaultsQoS(), - std::bind(&OdomSmoother::odomCallback, this, std::placeholders::_1)); - - odom_cumulate_.twist.twist.linear.x = 0; - odom_cumulate_.twist.twist.linear.y = 0; - odom_cumulate_.twist.twist.linear.z = 0; - odom_cumulate_.twist.twist.angular.x = 0; - odom_cumulate_.twist.twist.angular.y = 0; - odom_cumulate_.twist.twist.angular.z = 0; -} - -OdomSmoother::OdomSmoother( - const nav2_util::LifecycleNode::WeakPtr & parent, - double filter_duration, - const std::string & odom_topic) -: odom_history_duration_(rclcpp::Duration::from_seconds(filter_duration)) -{ - auto node = parent.lock(); - odom_sub_ = node->create_subscription( - odom_topic, - rclcpp::SystemDefaultsQoS(), - std::bind(&OdomSmoother::odomCallback, this, std::placeholders::_1)); - - odom_cumulate_.twist.twist.linear.x = 0; - odom_cumulate_.twist.twist.linear.y = 0; - odom_cumulate_.twist.twist.linear.z = 0; - odom_cumulate_.twist.twist.angular.x = 0; - odom_cumulate_.twist.twist.angular.y = 0; - odom_cumulate_.twist.twist.angular.z = 0; -} - void OdomSmoother::odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg) { std::lock_guard lock(odom_mutex_); diff --git a/nav2_util/src/string_utils.cpp b/nav2_util/src/string_utils.cpp index df447b54921..ac16f4c1885 100644 --- a/nav2_util/src/string_utils.cpp +++ b/nav2_util/src/string_utils.cpp @@ -18,17 +18,6 @@ namespace nav2_util { -std::string strip_leading_slash(const std::string & in) -{ - std::string out = in; - - if ((!in.empty()) && (in[0] == '/')) { - out.erase(0, 1); - } - - return out; -} - Tokens split(const std::string & tokenstring, char delimiter) { Tokens tokens; diff --git a/nav2_util/test/CMakeLists.txt b/nav2_util/test/CMakeLists.txt index 9ba40dfe512..4527fd8373d 100644 --- a/nav2_util/test/CMakeLists.txt +++ b/nav2_util/test/CMakeLists.txt @@ -1,31 +1,9 @@ ament_add_gtest(test_execution_timer test_execution_timer.cpp) target_link_libraries(test_execution_timer ${library_name}) -ament_add_gtest(test_node_utils test_node_utils.cpp) -target_link_libraries(test_node_utils ${library_name}) - -find_package(std_srvs REQUIRED) -find_package(test_msgs REQUIRED) - -ament_add_gtest(test_service_client test_service_client.cpp) -target_link_libraries(test_service_client ${library_name} ${std_srvs_TARGETS}) - -ament_add_gtest(test_service_server test_service_server.cpp) -target_link_libraries(test_service_server ${library_name} ${std_srvs_TARGETS}) - ament_add_gtest(test_string_utils test_string_utils.cpp) target_link_libraries(test_string_utils ${library_name}) -find_package(rclcpp_lifecycle REQUIRED) -ament_add_gtest(test_lifecycle_utils test_lifecycle_utils.cpp) -target_link_libraries(test_lifecycle_utils ${library_name} rclcpp_lifecycle::rclcpp_lifecycle) - -ament_add_gtest(test_actions test_actions.cpp) -target_link_libraries(test_actions ${library_name} rclcpp_action::rclcpp_action ${test_msgs_TARGETS}) - -ament_add_gtest(test_lifecycle_node test_lifecycle_node.cpp) -target_link_libraries(test_lifecycle_node ${library_name} rclcpp_lifecycle::rclcpp_lifecycle) - ament_add_gtest(test_lifecycle_cli_node test_lifecycle_cli_node.cpp) target_link_libraries(test_lifecycle_cli_node ${library_name} rclcpp_lifecycle::rclcpp_lifecycle) @@ -51,6 +29,3 @@ target_link_libraries(test_twist_publisher ${library_name} rclcpp::rclcpp ${geom ament_add_gtest(test_twist_subscriber test_twist_subscriber.cpp) target_link_libraries(test_twist_subscriber ${library_name} rclcpp::rclcpp ${geometry_msgs_TARGETS}) - -ament_add_gtest(test_validation_messages test_validation_messages.cpp) -target_link_libraries(test_validation_messages ${library_name} ${builtin_interfaces_TARGETS} ${std_msgs_TARGETS} ${geometry_msgs_TARGETS}) diff --git a/nav2_util/test/test_lifecycle_cli_node.cpp b/nav2_util/test/test_lifecycle_cli_node.cpp index 0efc9f69697..f6256a7a21e 100644 --- a/nav2_util/test/test_lifecycle_cli_node.cpp +++ b/nav2_util/test/test_lifecycle_cli_node.cpp @@ -18,28 +18,27 @@ #include #include #include "gtest/gtest.h" -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/lifecycle_utils.hpp" -#include "nav2_util/node_thread.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_thread.hpp" #include "rclcpp/rclcpp.hpp" #ifdef _WIN32 #include #endif -class DummyNode : public nav2_util::LifecycleNode +class DummyNode : public nav2::LifecycleNode { public: DummyNode() - : nav2_util::LifecycleNode("nav2_test_cli", "") + : nav2::LifecycleNode("nav2_test_cli", "") { activated = false; } - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & /*state*/) { activated = true; - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } bool activated; @@ -51,7 +50,7 @@ class Handle Handle() { node = std::make_shared(); - thread = std::make_shared(node->get_node_base_interface()); + thread = std::make_shared(node->get_node_base_interface()); } ~Handle() { @@ -59,7 +58,7 @@ class Handle node.reset(); } - std::shared_ptr thread; + std::shared_ptr thread; std::shared_ptr node; }; diff --git a/nav2_util/test/test_lifecycle_utils.cpp b/nav2_util/test/test_lifecycle_utils.cpp deleted file mode 100644 index f6a5076082b..00000000000 --- a/nav2_util/test/test_lifecycle_utils.cpp +++ /dev/null @@ -1,65 +0,0 @@ -// Copyright (c) 2019 Intel Corporation -// -// 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 -#include - -#include "gtest/gtest.h" -#include "nav2_util/lifecycle_utils.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "rclcpp/rclcpp.hpp" - -using nav2_util::startup_lifecycle_nodes; -using nav2_util::reset_lifecycle_nodes; - -void SpinNodesUntilDone( - std::vector nodes, - std::atomic * test_done) -{ - rclcpp::executors::SingleThreadedExecutor exec; - for (const auto & node : nodes) { - exec.add_node(node->get_node_base_interface()); - } - while (rclcpp::ok() && !(*test_done)) { - exec.spin_some(); - } -} - -TEST(Lifecycle, interface) -{ - std::vector nodes; - nodes.push_back(rclcpp_lifecycle::LifecycleNode::make_shared("foo")); - nodes.push_back(rclcpp_lifecycle::LifecycleNode::make_shared("bar")); - - std::atomic done(false); - std::thread node_thread(SpinNodesUntilDone, nodes, &done); - startup_lifecycle_nodes("/foo:/bar"); - reset_lifecycle_nodes("/foo:/bar"); - done = true; - node_thread.join(); - SUCCEED(); -} - -int main(int argc, char **argv) -{ - ::testing::InitGoogleTest(&argc, argv); - - rclcpp::init(0, nullptr); - - int result = RUN_ALL_TESTS(); - - rclcpp::shutdown(); - - return result; -} diff --git a/nav2_util/test/test_odometry_utils.cpp b/nav2_util/test/test_odometry_utils.cpp index e799ebf223d..5b8087e097e 100644 --- a/nav2_util/test/test_odometry_utils.cpp +++ b/nav2_util/test/test_odometry_utils.cpp @@ -15,7 +15,7 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/odometry_utils.hpp" #include "nav_msgs/msg/odometry.hpp" #include "geometry_msgs/msg/twist.hpp" @@ -26,7 +26,9 @@ using namespace std::chrono_literals; // NOLINT TEST(OdometryUtils, test_uninitialized) { - auto node = std::make_shared("test_node"); + auto node = std::make_shared("test_node"); + node->configure(); + node->activate(); nav2_util::OdomSmoother odom_smoother(node, 0.3, "odom"); geometry_msgs::msg::Twist twist_msg; geometry_msgs::msg::TwistStamped twist_stamped_msg; @@ -50,12 +52,18 @@ TEST(OdometryUtils, test_uninitialized) EXPECT_EQ(twist_stamped_msg.twist.linear.x, 0.0); EXPECT_EQ(twist_stamped_msg.twist.linear.y, 0.0); EXPECT_EQ(twist_stamped_msg.twist.angular.z, 0.0); + node->deactivate(); + node->cleanup(); + node.reset(); } TEST(OdometryUtils, test_smoothed_velocity) { - auto node = std::make_shared("test_node"); - auto odom_pub = node->create_publisher("odom", 1); + auto node = std::make_shared("test_node"); + auto odom_pub = node->create_publisher("odom"); + node->configure(); + node->activate(); + odom_pub->on_activate(); nav2_util::OdomSmoother odom_smoother(node, 0.3, "odom"); @@ -71,7 +79,7 @@ TEST(OdometryUtils, test_smoothed_velocity) odom_msg.twist.twist.angular.z = 1.0; odom_pub->publish(odom_msg); - rclcpp::spin_some(node); + rclcpp::spin_some(node->get_node_base_interface()); twist_msg = odom_smoother.getTwist(); EXPECT_EQ(twist_msg.linear.x, 1.0); @@ -85,7 +93,7 @@ TEST(OdometryUtils, test_smoothed_velocity) odom_pub->publish(odom_msg); std::this_thread::sleep_for(100ms); - rclcpp::spin_some(node); + rclcpp::spin_some(node->get_node_base_interface()); twist_msg = odom_smoother.getTwist(); twist_raw_msg = odom_smoother.getRawTwist(); @@ -103,7 +111,7 @@ TEST(OdometryUtils, test_smoothed_velocity) odom_pub->publish(odom_msg); std::this_thread::sleep_for(100ms); - rclcpp::spin_some(node); + rclcpp::spin_some(node->get_node_base_interface()); twist_msg = odom_smoother.getTwist(); twist_raw_msg = odom_smoother.getRawTwist(); @@ -121,7 +129,7 @@ TEST(OdometryUtils, test_smoothed_velocity) odom_pub->publish(odom_msg); std::this_thread::sleep_for(100ms); - rclcpp::spin_some(node); + rclcpp::spin_some(node->get_node_base_interface()); twist_msg = odom_smoother.getTwist(); twist_raw_msg = odom_smoother.getRawTwist(); @@ -139,7 +147,7 @@ TEST(OdometryUtils, test_smoothed_velocity) odom_pub->publish(odom_msg); std::this_thread::sleep_for(100ms); - rclcpp::spin_some(node); + rclcpp::spin_some(node->get_node_base_interface()); twist_msg = odom_smoother.getTwist(); twist_raw_msg = odom_smoother.getRawTwist(); diff --git a/nav2_util/test/test_robot_utils.cpp b/nav2_util/test/test_robot_utils.cpp index fbc3d8eceb4..119addc9355 100644 --- a/nav2_util/test/test_robot_utils.cpp +++ b/nav2_util/test/test_robot_utils.cpp @@ -14,19 +14,18 @@ #include #include -#include "rclcpp/rclcpp.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_util/robot_utils.hpp" #include "tf2_ros/transform_listener.h" #include "tf2_ros/transform_broadcaster.h" #include "geometry_msgs/msg/pose_stamped.hpp" #include "gtest/gtest.h" -#include "nav2_util/node_thread.hpp" #include "tf2_ros/create_timer_ros.h" TEST(RobotUtils, LookupExceptionError) { rclcpp::init(0, nullptr); - auto node = std::make_shared("name", rclcpp::NodeOptions()); + auto node = std::make_shared("name"); geometry_msgs::msg::PoseStamped global_pose; tf2_ros::Buffer tf(node->get_clock()); ASSERT_FALSE(nav2_util::getCurrentPose(global_pose, tf, "map", "base_link", 0.1)); diff --git a/nav2_util/test/test_string_utils.cpp b/nav2_util/test/test_string_utils.cpp index 488bd1ea006..bf73c280271 100644 --- a/nav2_util/test/test_string_utils.cpp +++ b/nav2_util/test/test_string_utils.cpp @@ -28,5 +28,4 @@ TEST(Split, SplitFunction) ASSERT_EQ(split("foo:bar:", ':'), Tokens({"foo", "bar", ""})); ASSERT_EQ(split(":", ':'), Tokens({"", ""})); ASSERT_EQ(split("foo::bar", ':'), Tokens({"foo", "", "bar"})); - ASSERT_TRUE(nav2_util::strip_leading_slash(std::string("/hi")) == std::string("hi")); } diff --git a/nav2_util/test/test_twist_publisher.cpp b/nav2_util/test/test_twist_publisher.cpp index be185b47f74..dc3b307984f 100644 --- a/nav2_util/test/test_twist_publisher.cpp +++ b/nav2_util/test/test_twist_publisher.cpp @@ -16,21 +16,18 @@ #include #include "nav2_util/twist_publisher.hpp" -#include "nav2_util/lifecycle_utils.hpp" #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" -using nav2_util::startup_lifecycle_nodes; -using nav2_util::reset_lifecycle_nodes; - TEST(TwistPublisher, Unstamped) { rclcpp::init(0, nullptr); - auto pub_node = std::make_shared("pub_node", ""); + auto pub_node = std::make_shared("pub_node", ""); pub_node->configure(); pub_node->declare_parameter("enable_stamped_cmd_vel", rclcpp::ParameterValue(false)); - auto vel_publisher = std::make_unique(pub_node, "cmd_vel", 1); + auto vel_publisher = std::make_unique( + pub_node, "cmd_vel", rclcpp::QoS(1)); ASSERT_EQ(vel_publisher->get_subscription_count(), 0); EXPECT_FALSE(vel_publisher->is_activated()); pub_node->activate(); @@ -38,7 +35,7 @@ TEST(TwistPublisher, Unstamped) vel_publisher->on_activate(); auto pub_thread = std::thread([&]() {rclcpp::spin(pub_node->get_node_base_interface());}); - auto sub_node = std::make_shared("sub_node", ""); + auto sub_node = std::make_shared("sub_node", ""); sub_node->configure(); sub_node->activate(); @@ -48,7 +45,7 @@ TEST(TwistPublisher, Unstamped) geometry_msgs::msg::Twist sub_msg {}; auto my_sub = sub_node->create_subscription( - "cmd_vel", 10, + "cmd_vel", [&](const geometry_msgs::msg::Twist msg) {sub_msg = msg;}); vel_publisher->publish(std::move(pub_msg)); @@ -66,17 +63,17 @@ TEST(TwistPublisher, Unstamped) TEST(TwistPublisher, Stamped) { rclcpp::init(0, nullptr); - auto pub_node = std::make_shared("pub_node", ""); + auto pub_node = std::make_shared("pub_node", ""); pub_node->declare_parameter("enable_stamped_cmd_vel", true); pub_node->configure(); - auto vel_publisher = std::make_unique(pub_node, "cmd_vel", 1); + auto vel_publisher = std::make_unique(pub_node, "cmd_vel"); ASSERT_EQ(vel_publisher->get_subscription_count(), 0); EXPECT_FALSE(vel_publisher->is_activated()); pub_node->activate(); EXPECT_TRUE(vel_publisher->is_activated()); auto pub_thread = std::thread([&]() {rclcpp::spin(pub_node->get_node_base_interface());}); - auto sub_node = std::make_shared("sub_node", ""); + auto sub_node = std::make_shared("sub_node", ""); sub_node->configure(); sub_node->activate(); @@ -87,7 +84,7 @@ TEST(TwistPublisher, Stamped) geometry_msgs::msg::TwistStamped sub_msg {}; auto my_sub = sub_node->create_subscription( - "cmd_vel", 10, + "cmd_vel", [&](const geometry_msgs::msg::TwistStamped msg) {sub_msg = msg;}); vel_publisher->publish(std::move(pub_msg)); diff --git a/nav2_util/test/test_twist_subscriber.cpp b/nav2_util/test/test_twist_subscriber.cpp index c18553bc391..8e30b6eec21 100644 --- a/nav2_util/test/test_twist_subscriber.cpp +++ b/nav2_util/test/test_twist_subscriber.cpp @@ -26,26 +26,27 @@ TEST(TwistSubscriber, Unstamped) { rclcpp::init(0, nullptr); - auto sub_node = std::make_shared("sub_node", ""); + auto sub_node = std::make_shared("sub_node", ""); sub_node->configure(); sub_node->activate(); sub_node->declare_parameter("enable_stamped_cmd_vel", rclcpp::ParameterValue(false)); geometry_msgs::msg::TwistStamped sub_msg {}; auto vel_subscriber = std::make_unique( - sub_node, "cmd_vel", 1, + sub_node, "cmd_vel", [&](const geometry_msgs::msg::Twist msg) {sub_msg.twist = msg;}, - [&](const geometry_msgs::msg::TwistStamped msg) {sub_msg = msg;} + [&](const geometry_msgs::msg::TwistStamped msg) {sub_msg = msg;}, + rclcpp::QoS(1) ); - auto pub_node = std::make_shared("pub_node", ""); + auto pub_node = std::make_shared("pub_node", ""); pub_node->configure(); geometry_msgs::msg::TwistStamped pub_msg {}; pub_msg.twist.linear.x = 42.0; auto vel_pub = - pub_node->create_publisher("cmd_vel", 1); + pub_node->create_publisher("cmd_vel"); pub_node->activate(); vel_pub->on_activate(); @@ -63,26 +64,26 @@ TEST(TwistSubscriber, Unstamped) TEST(TwistSubscriber, Stamped) { rclcpp::init(0, nullptr); - auto sub_node = std::make_shared("sub_node", ""); + auto sub_node = std::make_shared("sub_node", ""); sub_node->declare_parameter("enable_stamped_cmd_vel", true); sub_node->configure(); sub_node->activate(); geometry_msgs::msg::TwistStamped sub_msg {}; auto vel_subscriber = std::make_unique( - sub_node, "cmd_vel", 1, + sub_node, "cmd_vel", [&](const geometry_msgs::msg::Twist msg) {sub_msg.twist = msg;}, [&](const geometry_msgs::msg::TwistStamped msg) {sub_msg = msg;} ); - auto pub_node = std::make_shared("pub_node", ""); + auto pub_node = std::make_shared("pub_node", ""); pub_node->configure(); geometry_msgs::msg::TwistStamped pub_msg {}; pub_msg.twist.linear.x = 42.0; auto vel_pub = - pub_node->create_publisher("cmd_vel", 1); + pub_node->create_publisher("cmd_vel"); pub_node->activate(); vel_pub->on_activate(); diff --git a/nav2_velocity_smoother/CMakeLists.txt b/nav2_velocity_smoother/CMakeLists.txt index 7e1e3cb6b96..20c02e9194a 100644 --- a/nav2_velocity_smoother/CMakeLists.txt +++ b/nav2_velocity_smoother/CMakeLists.txt @@ -8,6 +8,7 @@ find_package(nav2_util REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(rclcpp_lifecycle REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -22,6 +23,7 @@ target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geometry_msgs_TARGETS} @@ -76,5 +78,6 @@ ament_export_dependencies( nav2_util rclcpp rclcpp_lifecycle + nav2_ros_common ) ament_package() diff --git a/nav2_velocity_smoother/include/nav2_velocity_smoother/velocity_smoother.hpp b/nav2_velocity_smoother/include/nav2_velocity_smoother/velocity_smoother.hpp index f69a827a7db..a5756ee12ba 100644 --- a/nav2_velocity_smoother/include/nav2_velocity_smoother/velocity_smoother.hpp +++ b/nav2_velocity_smoother/include/nav2_velocity_smoother/velocity_smoother.hpp @@ -22,8 +22,8 @@ #include #include -#include "nav2_util/lifecycle_node.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/odometry_utils.hpp" #include "nav2_util/robot_utils.hpp" #include "nav2_util/twist_publisher.hpp" @@ -38,7 +38,7 @@ namespace nav2_velocity_smoother * @class nav2_velocity_smoother::VelocitySmoother * @brief This class that smooths cmd_vel velocities for robot bases */ -class VelocitySmoother : public nav2_util::LifecycleNode +class VelocitySmoother : public nav2::LifecycleNode { public: /** @@ -83,35 +83,35 @@ class VelocitySmoother : public nav2_util::LifecycleNode * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activates member variables * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivates member variables * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Calls clean up states and resets member variables. * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in Shutdown state * @param state LifeCycle Node's state * @return Success or Failure */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** * @brief Callback for incoming velocity commands diff --git a/nav2_velocity_smoother/package.xml b/nav2_velocity_smoother/package.xml index f2a0c2cd61b..b0ed66dd3e6 100644 --- a/nav2_velocity_smoother/package.xml +++ b/nav2_velocity_smoother/package.xml @@ -15,6 +15,8 @@ rclcpp rclcpp_components rclcpp_lifecycle + nav2_ros_common + ament_cmake_gtest ament_lint_common diff --git a/nav2_velocity_smoother/src/velocity_smoother.cpp b/nav2_velocity_smoother/src/velocity_smoother.cpp index cfce20042ff..20547c53e12 100644 --- a/nav2_velocity_smoother/src/velocity_smoother.cpp +++ b/nav2_velocity_smoother/src/velocity_smoother.cpp @@ -22,7 +22,7 @@ #include "nav2_velocity_smoother/velocity_smoother.hpp" using namespace std::chrono_literals; -using nav2_util::declare_parameter_if_not_declared; +using nav2::declare_parameter_if_not_declared; using std::placeholders::_1; using rcl_interfaces::msg::ParameterType; @@ -43,7 +43,7 @@ VelocitySmoother::~VelocitySmoother() } } -nav2_util::CallbackReturn +nav2::CallbackReturn VelocitySmoother::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring velocity smoother"); @@ -80,31 +80,31 @@ VelocitySmoother::on_configure(const rclcpp_lifecycle::State & state) get_logger(), "Positive values set of deceleration! These should be negative to slow down!"); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } if (max_accels_[i] < 0.0) { RCLCPP_ERROR( get_logger(), "Negative values set of acceleration! These should be positive to speed up!"); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } if (min_velocities_[i] > 0.0) { RCLCPP_ERROR( get_logger(), "Positive values set of min_velocities! These should be negative!"); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } if (max_velocities_[i] < 0.0) { RCLCPP_ERROR( get_logger(), "Negative values set of max_velocities! These should be positive!"); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } if (min_velocities_[i] > max_velocities_[i]) { RCLCPP_ERROR(get_logger(), "Min velocities are higher than max velocities!"); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } @@ -128,7 +128,7 @@ VelocitySmoother::on_configure(const rclcpp_lifecycle::State & state) "Invalid setting of kinematic and/or deadband limits!" " All limits must be size of 3 representing (x, y, theta)."); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } // Get control type @@ -142,35 +142,34 @@ VelocitySmoother::on_configure(const rclcpp_lifecycle::State & state) get_logger(), "Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP."); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } // Setup inputs / outputs - smoothed_cmd_pub_ = std::make_unique(node, "cmd_vel_smoothed", 1); + smoothed_cmd_pub_ = std::make_unique(node, "cmd_vel_smoothed"); cmd_sub_ = std::make_unique( node, - "cmd_vel", rclcpp::QoS(1), + "cmd_vel", std::bind(&VelocitySmoother::inputCommandCallback, this, std::placeholders::_1), - std::bind(&VelocitySmoother::inputCommandStampedCallback, this, std::placeholders::_1) - ); + std::bind(&VelocitySmoother::inputCommandStampedCallback, this, std::placeholders::_1)); declare_parameter_if_not_declared(node, "use_realtime_priority", rclcpp::ParameterValue(false)); bool use_realtime_priority = false; node->get_parameter("use_realtime_priority", use_realtime_priority); if (use_realtime_priority) { try { - nav2_util::setSoftRealTimePriority(); + nav2::setSoftRealTimePriority(); } catch (const std::runtime_error & e) { RCLCPP_ERROR(get_logger(), "%s", e.what()); on_cleanup(state); - return nav2_util::CallbackReturn::FAILURE; + return nav2::CallbackReturn::FAILURE; } } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn VelocitySmoother::on_activate(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Activating"); @@ -185,10 +184,10 @@ VelocitySmoother::on_activate(const rclcpp_lifecycle::State &) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn VelocitySmoother::on_deactivate(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -203,24 +202,24 @@ VelocitySmoother::on_deactivate(const rclcpp_lifecycle::State &) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn VelocitySmoother::on_cleanup(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Cleaning up"); smoothed_cmd_pub_.reset(); odom_smoother_.reset(); cmd_sub_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn VelocitySmoother::on_shutdown(const rclcpp_lifecycle::State &) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } void VelocitySmoother::inputCommandStampedCallback( diff --git a/nav2_velocity_smoother/test/test_velocity_smoother.cpp b/nav2_velocity_smoother/test/test_velocity_smoother.cpp index 00144bb5769..190b7b5ef3e 100644 --- a/nav2_velocity_smoother/test/test_velocity_smoother.cpp +++ b/nav2_velocity_smoother/test/test_velocity_smoother.cpp @@ -32,7 +32,7 @@ class VelSmootherShim : public nav2_velocity_smoother::VelocitySmoother public: VelSmootherShim() : VelocitySmoother() {} - nav2_util::CallbackReturn configure(const rclcpp_lifecycle::State & state) + nav2::CallbackReturn configure(const rclcpp_lifecycle::State & state) { return this->on_configure(state); } @@ -68,7 +68,6 @@ TEST(VelocitySmootherTest, openLoopTestTimer) auto subscription = nav2_util::TwistSubscriber( smoother, "cmd_vel_smoothed", - 1, [&](geometry_msgs::msg::Twist::SharedPtr msg) { linear_vels.push_back(msg->linear.x); }, [&](geometry_msgs::msg::TwistStamped::SharedPtr msg) { @@ -122,14 +121,13 @@ TEST(VelocitySmootherTest, approxClosedLoopTestTimer) auto subscription = nav2_util::TwistSubscriber( smoother, "cmd_vel_smoothed", - 1, [&](geometry_msgs::msg::Twist::SharedPtr msg) { linear_vels.push_back(msg->linear.x); }, [&](geometry_msgs::msg::TwistStamped::SharedPtr msg) { linear_vels.push_back(msg->twist.linear.x); }); - auto odom_pub = smoother->create_publisher("odom", 1); + auto odom_pub = smoother->create_publisher("odom"); odom_pub->on_activate(); nav_msgs::msg::Odometry odom_msg; odom_msg.header.frame_id = "odom"; @@ -563,7 +561,7 @@ TEST(VelocitySmootherTest, testCommandCallback) smoother->configure(state); smoother->activate(state); - auto pub = smoother->create_publisher("cmd_vel", 1); + auto pub = smoother->create_publisher("cmd_vel"); pub->on_activate(); auto msg = std::make_unique(); msg->twist.linear.x = 100.0; @@ -592,10 +590,10 @@ TEST(VelocitySmootherTest, testInvalidParams) std::vector max_vels{0.0, 0.0}; // invalid size smoother->declare_parameter("max_velocity", rclcpp::ParameterValue(max_vels)); rclcpp_lifecycle::State state; - EXPECT_EQ(smoother->configure(state), nav2_util::CallbackReturn::FAILURE); + EXPECT_EQ(smoother->configure(state), nav2::CallbackReturn::FAILURE); smoother->set_parameter(rclcpp::Parameter("feedback", std::string("LAWLS"))); - EXPECT_EQ(smoother->configure(state), nav2_util::CallbackReturn::FAILURE); + EXPECT_EQ(smoother->configure(state), nav2::CallbackReturn::FAILURE); } TEST(VelocitySmootherTest, testInvalidParamsAccelDecel) @@ -611,13 +609,13 @@ TEST(VelocitySmootherTest, testInvalidParamsAccelDecel) smoother->declare_parameter("max_velocity", rclcpp::ParameterValue(bad_test_max_vel)); smoother->declare_parameter("min_velocity", rclcpp::ParameterValue(bad_test_min_vel)); rclcpp_lifecycle::State state; - EXPECT_EQ(smoother->configure(state), nav2_util::CallbackReturn::FAILURE); + EXPECT_EQ(smoother->configure(state), nav2::CallbackReturn::FAILURE); smoother->set_parameter(rclcpp::Parameter("max_accel", rclcpp::ParameterValue(bad_test_accel))); - EXPECT_EQ(smoother->configure(state), nav2_util::CallbackReturn::FAILURE); + EXPECT_EQ(smoother->configure(state), nav2::CallbackReturn::FAILURE); smoother->set_parameter(rclcpp::Parameter("max_decel", rclcpp::ParameterValue(bad_test_decel))); - EXPECT_EQ(smoother->configure(state), nav2_util::CallbackReturn::FAILURE); + EXPECT_EQ(smoother->configure(state), nav2::CallbackReturn::FAILURE); } TEST(VelocitySmootherTest, testDynamicParameter) diff --git a/nav2_waypoint_follower/CMakeLists.txt b/nav2_waypoint_follower/CMakeLists.txt index 7dd40fdddd8..da8c358b2f8 100644 --- a/nav2_waypoint_follower/CMakeLists.txt +++ b/nav2_waypoint_follower/CMakeLists.txt @@ -21,6 +21,7 @@ find_package(robot_localization REQUIRED) find_package(sensor_msgs REQUIRED) find_package(std_msgs REQUIRED) find_package(tf2_ros REQUIRED) +find_package(nav2_ros_common REQUIRED) nav2_package() @@ -34,6 +35,7 @@ add_library(${library_name} SHARED target_include_directories(${library_name} PUBLIC "$" "$" + "$" ) target_link_libraries(${library_name} PUBLIC ${geographic_msgs_TARGETS} @@ -68,6 +70,7 @@ add_executable(${executable_name} target_include_directories(${executable_name} PRIVATE "$" "$" + "$" ) target_link_libraries(${executable_name} PRIVATE ${library_name} @@ -78,6 +81,7 @@ add_library(wait_at_waypoint SHARED plugins/wait_at_waypoint.cpp) target_include_directories(wait_at_waypoint PUBLIC "$" "$" + "$" ) target_link_libraries(wait_at_waypoint PUBLIC ${geometry_msgs_TARGETS} @@ -94,6 +98,7 @@ add_library(photo_at_waypoint SHARED plugins/photo_at_waypoint.cpp) target_include_directories(photo_at_waypoint PUBLIC "$" "$" + "$" ) target_link_libraries(photo_at_waypoint PUBLIC cv_bridge::cv_bridge @@ -114,6 +119,7 @@ add_library(input_at_waypoint SHARED plugins/input_at_waypoint.cpp) target_include_directories(input_at_waypoint PUBLIC "$" "$" + "$" ) target_link_libraries(input_at_waypoint PUBLIC ${geometry_msgs_TARGETS} @@ -167,6 +173,7 @@ ament_export_dependencies( OpenCV pluginlib rclcpp + nav2_ros_common rclcpp_action rclcpp_lifecycle robot_localization diff --git a/nav2_waypoint_follower/README.md b/nav2_waypoint_follower/README.md index c906eba2ff9..f529692b885 100644 --- a/nav2_waypoint_follower/README.md +++ b/nav2_waypoint_follower/README.md @@ -41,7 +41,7 @@ For instance, ```cpp using ClientT = nav2_msgs::action::FollowGPSWaypoints; -rclcpp_action::Client::SharedPtr gps_waypoint_follower_action_client_; +nav2::ActionClient::SharedPtr gps_waypoint_follower_action_client_; gps_waypoint_follower_action_client_ = rclcpp_action::create_client(this, "follow_gps_waypoints"); ``` diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/input_at_waypoint.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/input_at_waypoint.hpp index 8be79fcb8e0..6d406527014 100644 --- a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/input_at_waypoint.hpp +++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/input_at_waypoint.hpp @@ -52,7 +52,7 @@ class InputAtWaypoint : public nav2_core::WaypointTaskExecutor * @param plugin_name name of plugin */ void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name); /** @@ -77,7 +77,7 @@ class InputAtWaypoint : public nav2_core::WaypointTaskExecutor rclcpp::Logger logger_{rclcpp::get_logger("nav2_waypoint_follower")}; rclcpp::Clock::SharedPtr clock_; std::mutex mutex_; - rclcpp::Subscription::SharedPtr subscription_; + nav2::Subscription::SharedPtr subscription_; }; } // namespace nav2_waypoint_follower diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp index 8b5b2aaf150..fe2bb9b55bc 100644 --- a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp +++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/photo_at_waypoint.hpp @@ -55,7 +55,7 @@ class PhotoAtWaypoint : public nav2_core::WaypointTaskExecutor * @param plugin_name should be provided in nav2_params.yaml==> waypoint_follower */ void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name); @@ -101,7 +101,7 @@ class PhotoAtWaypoint : public nav2_core::WaypointTaskExecutor // global logger rclcpp::Logger logger_{rclcpp::get_logger("nav2_waypoint_follower")}; // ros subscriber to get camera image - rclcpp::Subscription::SharedPtr camera_image_subscriber_; + nav2::Subscription::SharedPtr camera_image_subscriber_; }; } // namespace nav2_waypoint_follower diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/wait_at_waypoint.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/wait_at_waypoint.hpp index c6e6ab09fd0..1fdb13b2131 100644 --- a/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/wait_at_waypoint.hpp +++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/plugins/wait_at_waypoint.hpp @@ -53,7 +53,7 @@ class WaitAtWaypoint : public nav2_core::WaypointTaskExecutor * @param plugin_name */ void initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name); diff --git a/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp b/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp index 24e0948c8a0..83edf012880 100644 --- a/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp +++ b/nav2_waypoint_follower/include/nav2_waypoint_follower/waypoint_follower.hpp @@ -24,16 +24,16 @@ #include "pluginlib/class_loader.hpp" #include "pluginlib/class_list_macros.hpp" #include "geographic_msgs/msg/geo_pose.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_msgs/action/navigate_to_pose.hpp" #include "nav2_msgs/action/follow_waypoints.hpp" #include "nav2_msgs/msg/waypoint_status.hpp" #include "nav_msgs/msg/path.hpp" -#include "nav2_util/simple_action_server.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/simple_action_server.hpp" +#include "nav2_ros_common/node_utils.hpp" #include "nav2_util/string_utils.hpp" #include "nav2_msgs/action/follow_gps_waypoints.hpp" -#include "nav2_util/service_client.hpp" +#include "nav2_ros_common/service_client.hpp" #include "nav2_core/waypoint_task_executor.hpp" #include "robot_localization/srv/from_ll.hpp" @@ -64,17 +64,17 @@ struct GoalStatus * @brief An action server that uses behavior tree for navigating a robot to its * goal position. */ -class WaypointFollower : public nav2_util::LifecycleNode +class WaypointFollower : public nav2::LifecycleNode { public: using ActionT = nav2_msgs::action::FollowWaypoints; using ClientT = nav2_msgs::action::NavigateToPose; - using ActionServer = nav2_util::SimpleActionServer; - using ActionClient = rclcpp_action::Client; + using ActionServer = nav2::SimpleActionServer; + using ActionClient = nav2::ActionClient; // Shorten the types for GPS waypoint following using ActionTGPS = nav2_msgs::action::FollowGPSWaypoints; - using ActionServerGPS = nav2_util::SimpleActionServer; + using ActionServerGPS = nav2::SimpleActionServer; /** * @brief A constructor for nav2_waypoint_follower::WaypointFollower class @@ -94,31 +94,31 @@ class WaypointFollower : public nav2_util::LifecycleNode * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override; /** * @brief Activates action server * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override; /** * @brief Deactivates action server * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override; /** * @brief Resets member variables * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override; /** * @brief Called when in shutdown state * @param state Reference to LifeCycle node state * @return SUCCESS or FAILURE */ - nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; + nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override; /** * @brief Templated function to perform internal logic behind waypoint following, @@ -199,16 +199,15 @@ class WaypointFollower : public nav2_util::LifecycleNode rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_; // Our action server - std::unique_ptr xyz_action_server_; + typename ActionServer::SharedPtr xyz_action_server_; ActionClient::SharedPtr nav_to_pose_client_; rclcpp::CallbackGroup::SharedPtr callback_group_; rclcpp::executors::SingleThreadedExecutor callback_group_executor_; std::shared_future::SharedPtr> future_goal_handle_; // Our action server for GPS waypoint following - std::unique_ptr gps_action_server_; - std::unique_ptr>> from_ll_to_map_client_; + typename ActionServerGPS::SharedPtr gps_action_server_; + nav2::ServiceClient::SharedPtr from_ll_to_map_client_; bool stop_on_failure_; int loop_rate_; diff --git a/nav2_waypoint_follower/package.xml b/nav2_waypoint_follower/package.xml index 409e652d8ff..4aa90590587 100644 --- a/nav2_waypoint_follower/package.xml +++ b/nav2_waypoint_follower/package.xml @@ -27,6 +27,7 @@ sensor_msgs std_msgs tf2_ros + nav2_ros_common ament_cmake_gtest ament_lint_auto diff --git a/nav2_waypoint_follower/plugins/input_at_waypoint.cpp b/nav2_waypoint_follower/plugins/input_at_waypoint.cpp index b6b4f84b9a5..58570b9c000 100644 --- a/nav2_waypoint_follower/plugins/input_at_waypoint.cpp +++ b/nav2_waypoint_follower/plugins/input_at_waypoint.cpp @@ -18,7 +18,7 @@ #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_waypoint_follower { @@ -37,7 +37,7 @@ InputAtWaypoint::~InputAtWaypoint() } void InputAtWaypoint::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { auto node = parent.lock(); @@ -51,13 +51,13 @@ void InputAtWaypoint::initialize( double timeout; std::string input_topic; - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".timeout", rclcpp::ParameterValue(10.0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".enabled", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".input_topic", rclcpp::ParameterValue("input_at_waypoint/input")); timeout = node->get_parameter(plugin_name + ".timeout").as_double(); @@ -69,7 +69,7 @@ void InputAtWaypoint::initialize( RCLCPP_INFO( logger_, "InputAtWaypoint: Subscribing to input topic %s.", input_topic.c_str()); subscription_ = node->create_subscription( - input_topic, 1, std::bind(&InputAtWaypoint::Cb, this, _1)); + input_topic, std::bind(&InputAtWaypoint::Cb, this, _1)); } void InputAtWaypoint::Cb(const std_msgs::msg::Empty::SharedPtr /*msg*/) diff --git a/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp b/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp index 77ff7f20aa0..f14b2c249c9 100644 --- a/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp +++ b/nav2_waypoint_follower/plugins/photo_at_waypoint.cpp @@ -19,7 +19,7 @@ #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_waypoint_follower { @@ -32,23 +32,23 @@ PhotoAtWaypoint::~PhotoAtWaypoint() } void PhotoAtWaypoint::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { auto node = parent.lock(); curr_frame_msg_ = std::make_shared(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".enabled", rclcpp::ParameterValue(true)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".image_topic", rclcpp::ParameterValue("/camera/color/image_raw")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".save_dir", rclcpp::ParameterValue("/tmp/waypoint_images")); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".image_format", rclcpp::ParameterValue("png")); @@ -93,7 +93,7 @@ void PhotoAtWaypoint::initialize( logger_, "Initializing photo at waypoint plugin, subscribing to camera topic named; %s", image_topic_.c_str()); camera_image_subscriber_ = node->create_subscription( - image_topic_, rclcpp::SystemDefaultsQoS(), + image_topic_, std::bind(&PhotoAtWaypoint::imageCallback, this, std::placeholders::_1)); } } diff --git a/nav2_waypoint_follower/plugins/wait_at_waypoint.cpp b/nav2_waypoint_follower/plugins/wait_at_waypoint.cpp index 77e20bcf768..bbfbd3de38e 100644 --- a/nav2_waypoint_follower/plugins/wait_at_waypoint.cpp +++ b/nav2_waypoint_follower/plugins/wait_at_waypoint.cpp @@ -19,7 +19,7 @@ #include "pluginlib/class_list_macros.hpp" -#include "nav2_util/node_utils.hpp" +#include "nav2_ros_common/node_utils.hpp" namespace nav2_waypoint_follower { @@ -34,7 +34,7 @@ WaitAtWaypoint::~WaitAtWaypoint() } void WaitAtWaypoint::initialize( - const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, + const nav2::LifecycleNode::WeakPtr & parent, const std::string & plugin_name) { auto node = parent.lock(); @@ -43,11 +43,11 @@ void WaitAtWaypoint::initialize( } logger_ = node->get_logger(); clock_ = node->get_clock(); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".waypoint_pause_duration", rclcpp::ParameterValue(0)); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( node, plugin_name + ".enabled", rclcpp::ParameterValue(true)); diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index cd3993dc4e0..62970ed46be 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -28,7 +28,7 @@ using rcl_interfaces::msg::ParameterType; using std::placeholders::_1; WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options) -: nav2_util::LifecycleNode("waypoint_follower", "", options), +: nav2::LifecycleNode("waypoint_follower", "", options), waypoint_task_executor_loader_("nav2_waypoint_follower", "nav2_core::WaypointTaskExecutor") { @@ -39,10 +39,10 @@ WaypointFollower::WaypointFollower(const rclcpp::NodeOptions & options) declare_parameter("global_frame_id", "map"); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( this, std::string("waypoint_task_executor_plugin"), rclcpp::ParameterValue(std::string("wait_at_waypoint"))); - nav2_util::declare_parameter_if_not_declared( + nav2::declare_parameter_if_not_declared( this, std::string("wait_at_waypoint.plugin"), rclcpp::ParameterValue(std::string("nav2_waypoint_follower::WaitAtWaypoint"))); } @@ -51,7 +51,7 @@ WaypointFollower::~WaypointFollower() { } -nav2_util::CallbackReturn +nav2::CallbackReturn WaypointFollower::on_configure(const rclcpp_lifecycle::State & state) { RCLCPP_INFO(get_logger(), "Configuring"); @@ -62,42 +62,26 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state) loop_rate_ = get_parameter("loop_rate").as_int(); waypoint_task_executor_id_ = get_parameter("waypoint_task_executor_plugin").as_string(); global_frame_id_ = get_parameter("global_frame_id").as_string(); - global_frame_id_ = nav2_util::strip_leading_slash(global_frame_id_); callback_group_ = create_callback_group( rclcpp::CallbackGroupType::MutuallyExclusive, false); callback_group_executor_.add_callback_group(callback_group_, get_node_base_interface()); - nav_to_pose_client_ = rclcpp_action::create_client( - get_node_base_interface(), - get_node_graph_interface(), - get_node_logging_interface(), - get_node_waitables_interface(), + nav_to_pose_client_ = create_action_client( "navigate_to_pose", callback_group_); - xyz_action_server_ = std::make_unique( - get_node_base_interface(), - get_node_clock_interface(), - get_node_logging_interface(), - get_node_waitables_interface(), + xyz_action_server_ = create_action_server( "follow_waypoints", std::bind( &WaypointFollower::followWaypointsCallback, this), nullptr, std::chrono::milliseconds( 500), false); - from_ll_to_map_client_ = std::make_unique< - nav2_util::ServiceClient>>( + from_ll_to_map_client_ = node->create_client( "/fromLL", - node, true /*creates and spins an internal executor*/); - gps_action_server_ = std::make_unique( - get_node_base_interface(), - get_node_clock_interface(), - get_node_logging_interface(), - get_node_waitables_interface(), + gps_action_server_ = create_action_server( "follow_gps_waypoints", std::bind( &WaypointFollower::followGPSWaypointsCallback, @@ -105,7 +89,7 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state) 500), false); try { - waypoint_task_executor_type_ = nav2_util::get_plugin_type_param( + waypoint_task_executor_type_ = nav2::get_plugin_type_param( this, waypoint_task_executor_id_); waypoint_task_executor_ = waypoint_task_executor_loader_.createUniqueInstance( @@ -121,10 +105,10 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & state) on_cleanup(state); } - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn WaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Activating"); @@ -140,10 +124,10 @@ WaypointFollower::on_activate(const rclcpp_lifecycle::State & /*state*/) // create bond connection createBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn WaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Deactivating"); @@ -155,10 +139,10 @@ WaypointFollower::on_deactivate(const rclcpp_lifecycle::State & /*state*/) // destroy bond connection destroyBond(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn WaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Cleaning up"); @@ -168,14 +152,14 @@ WaypointFollower::on_cleanup(const rclcpp_lifecycle::State & /*state*/) gps_action_server_.reset(); from_ll_to_map_client_.reset(); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } -nav2_util::CallbackReturn +nav2::CallbackReturn WaypointFollower::on_shutdown(const rclcpp_lifecycle::State & /*state*/) { RCLCPP_INFO(get_logger(), "Shutting down"); - return nav2_util::CallbackReturn::SUCCESS; + return nav2::CallbackReturn::SUCCESS; } template @@ -191,7 +175,7 @@ std::vector WaypointFollower::getLatestGoalPose } // compile time static check to decide which block of code to be built - if constexpr (std::is_same>::value) { + if constexpr (std::is_same::value) { // If normal waypoint following callback was called, we build here poses = current_goal->poses; } else { @@ -280,7 +264,7 @@ void WaypointFollower::followWaypointsHandler( client_goal.pose = poses[goal_index]; client_goal.pose.header.stamp = this->now(); - auto send_goal_options = rclcpp_action::Client::SendGoalOptions(); + auto send_goal_options = nav2::ActionClient::SendGoalOptions(); send_goal_options.result_callback = std::bind( &WaypointFollower::resultCallback, this, std::placeholders::_1); @@ -396,7 +380,7 @@ void WaypointFollower::followWaypointsCallback() auto feedback = std::make_shared(); auto result = std::make_shared(); - followWaypointsHandler, + followWaypointsHandler( xyz_action_server_, @@ -408,7 +392,7 @@ void WaypointFollower::followGPSWaypointsCallback() auto feedback = std::make_shared(); auto result = std::make_shared(); - followWaypointsHandler, + followWaypointsHandler( gps_action_server_, diff --git a/nav2_waypoint_follower/test/test_dynamic_parameters.cpp b/nav2_waypoint_follower/test/test_dynamic_parameters.cpp index 046de92fd66..8d13e7b797a 100644 --- a/nav2_waypoint_follower/test/test_dynamic_parameters.cpp +++ b/nav2_waypoint_follower/test/test_dynamic_parameters.cpp @@ -19,7 +19,7 @@ #include #include "gtest/gtest.h" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_waypoint_follower/waypoint_follower.hpp" #include "rclcpp/rclcpp.hpp" diff --git a/nav2_waypoint_follower/test/test_task_executors.cpp b/nav2_waypoint_follower/test/test_task_executors.cpp index 9b58d043120..726851be5d4 100644 --- a/nav2_waypoint_follower/test/test_task_executors.cpp +++ b/nav2_waypoint_follower/test/test_task_executors.cpp @@ -22,14 +22,14 @@ #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" -#include "nav2_util/lifecycle_node.hpp" +#include "nav2_ros_common/lifecycle_node.hpp" #include "nav2_waypoint_follower/plugins/photo_at_waypoint.hpp" #include "nav2_waypoint_follower/plugins/wait_at_waypoint.hpp" #include "nav2_waypoint_follower/plugins/input_at_waypoint.hpp" TEST(WaypointFollowerTest, WaitAtWaypoint) { - auto node = std::make_shared("testWaypointNode"); + auto node = std::make_shared("testWaypointNode"); node->declare_parameter("WAW.waypoint_pause_duration", 50); @@ -58,8 +58,8 @@ TEST(WaypointFollowerTest, WaitAtWaypoint) TEST(WaypointFollowerTest, InputAtWaypoint) { - auto node = std::make_shared("testWaypointNode"); - auto pub = node->create_publisher("input_at_waypoint/input", 1); + auto node = std::make_shared("testWaypointNode"); + auto pub = node->create_publisher("input_at_waypoint/input"); pub->on_activate(); auto publish_message = [&]() -> void @@ -100,8 +100,8 @@ TEST(WaypointFollowerTest, InputAtWaypoint) TEST(WaypointFollowerTest, PhotoAtWaypoint) { - auto node = std::make_shared("testWaypointNode"); - auto pub = node->create_publisher("/camera/color/image_raw", 1); + auto node = std::make_shared("testWaypointNode"); + auto pub = node->create_publisher("/camera/color/image_raw"); pub->on_activate(); std::condition_variable cv; std::mutex mtx; diff --git a/navigation2/package.xml b/navigation2/package.xml index 6aa4209831c..225861a4ef4 100644 --- a/navigation2/package.xml +++ b/navigation2/package.xml @@ -33,6 +33,7 @@ nav2_behaviors nav2_smoother nav2_regulated_pure_pursuit_controller + nav2_ros_common nav2_route nav2_rotation_shim_controller nav2_rviz_plugins diff --git a/tools/update_readme_table.py b/tools/update_readme_table.py index 5ca0a2d1d84..f15e4af05a8 100755 --- a/tools/update_readme_table.py +++ b/tools/update_readme_table.py @@ -47,6 +47,7 @@ 'nav2_planner', 'nav2_regulated_pure_pursuit_controller', 'nav2_rotation_shim_controller', + 'nav2_ros_common', 'nav2_route', 'nav2_rviz_plugins', 'nav2_simple_commander',