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 0294a817e4..79a5a7c37d 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 @@ -89,7 +89,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner protected: /** - * @brief Callback executed when a paramter change is detected + * @brief Callback executed when a parameter change is detected * @param event ParameterEvent message */ void on_parameter_event_callback(const rcl_interfaces::msg::ParameterEvent::SharedPtr event); 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 109913b7fd..4fd56731ac 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 @@ -87,21 +87,41 @@ class SmacPlannerHybrid : public nav2_core::GlobalPlanner const geometry_msgs::msg::PoseStamped & goal) override; protected: + /** + * @brief Callback executed when a parameter change is detected + * @param event ParameterEvent message + */ + void on_parameter_event_callback(const rcl_interfaces::msg::ParameterEvent::SharedPtr event); + std::unique_ptr> _a_star; GridCollisionChecker _collision_checker; std::unique_ptr _smoother; rclcpp::Clock::SharedPtr _clock; rclcpp::Logger _logger{rclcpp::get_logger("SmacPlannerHybrid")}; nav2_costmap_2d::Costmap2D * _costmap; + std::shared_ptr _costmap_ros; std::unique_ptr _costmap_downsampler; std::string _global_frame, _name; + float _lookup_table_dim; float _tolerance; + bool _downsample_costmap; int _downsampling_factor; - unsigned int _angle_quantizations; double _angle_bin_size; - bool _downsample_costmap; - rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; + unsigned int _angle_quantizations; + bool _allow_unknown; + int _max_iterations; + SearchInfo _search_info; double _max_planning_time; + double _lookup_table_size; + std::string _motion_model_for_search; + MotionModel _motion_model; + rclcpp_lifecycle::LifecyclePublisher::SharedPtr _raw_plan_publisher; + std::mutex _mutex; + rclcpp_lifecycle::LifecycleNode::WeakPtr _node; + + // Subscription for parameter change + rclcpp::AsyncParametersClient::SharedPtr _parameters_client; + rclcpp::Subscription::SharedPtr _parameter_event_sub; }; } // namespace nav2_smac_planner diff --git a/nav2_smac_planner/src/smac_planner_hybrid.cpp b/nav2_smac_planner/src/smac_planner_hybrid.cpp index 848ca3e0fb..f4e6498654 100644 --- a/nav2_smac_planner/src/smac_planner_hybrid.cpp +++ b/nav2_smac_planner/src/smac_planner_hybrid.cpp @@ -27,6 +27,8 @@ namespace nav2_smac_planner { using namespace std::chrono; // NOLINT +using rcl_interfaces::msg::ParameterType; +using std::placeholders::_1; SmacPlannerHybrid::SmacPlannerHybrid() : _a_star(nullptr), @@ -49,19 +51,16 @@ void SmacPlannerHybrid::configure( std::string name, std::shared_ptr/*tf*/, std::shared_ptr costmap_ros) { + _node = parent; auto node = parent.lock(); _logger = node->get_logger(); _clock = node->get_clock(); _costmap = costmap_ros->getCostmap(); + _costmap_ros = costmap_ros; _name = name; _global_frame = costmap_ros->getGlobalFrameID(); - bool allow_unknown; - int max_iterations; int angle_quantizations; - double lookup_table_size; - SearchInfo search_info; - std::string motion_model_for_search; // General planner params nav2_util::declare_parameter_if_not_declared( @@ -79,93 +78,93 @@ void SmacPlannerHybrid::configure( nav2_util::declare_parameter_if_not_declared( node, name + ".allow_unknown", rclcpp::ParameterValue(true)); - node->get_parameter(name + ".allow_unknown", allow_unknown); + node->get_parameter(name + ".allow_unknown", _allow_unknown); nav2_util::declare_parameter_if_not_declared( node, name + ".max_iterations", rclcpp::ParameterValue(1000000)); - node->get_parameter(name + ".max_iterations", max_iterations); + node->get_parameter(name + ".max_iterations", _max_iterations); nav2_util::declare_parameter_if_not_declared( node, name + ".minimum_turning_radius", rclcpp::ParameterValue(0.4)); - node->get_parameter(name + ".minimum_turning_radius", search_info.minimum_turning_radius); + node->get_parameter(name + ".minimum_turning_radius", _search_info.minimum_turning_radius); nav2_util::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); + node->get_parameter(name + ".cache_obstacle_heuristic", _search_info.cache_obstacle_heuristic); nav2_util::declare_parameter_if_not_declared( node, name + ".reverse_penalty", rclcpp::ParameterValue(2.0)); - node->get_parameter(name + ".reverse_penalty", search_info.reverse_penalty); + node->get_parameter(name + ".reverse_penalty", _search_info.reverse_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".change_penalty", rclcpp::ParameterValue(0.15)); - node->get_parameter(name + ".change_penalty", search_info.change_penalty); + node->get_parameter(name + ".change_penalty", _search_info.change_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".non_straight_penalty", rclcpp::ParameterValue(1.50)); - node->get_parameter(name + ".non_straight_penalty", search_info.non_straight_penalty); + node->get_parameter(name + ".non_straight_penalty", _search_info.non_straight_penalty); nav2_util::declare_parameter_if_not_declared( node, name + ".cost_penalty", rclcpp::ParameterValue(1.7)); - node->get_parameter(name + ".cost_penalty", search_info.cost_penalty); + node->get_parameter(name + ".cost_penalty", _search_info.cost_penalty); nav2_util::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); + node->get_parameter(name + ".analytic_expansion_ratio", _search_info.analytic_expansion_ratio); nav2_util::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( node, name + ".lookup_table_size", rclcpp::ParameterValue(20.0)); - node->get_parameter(name + ".lookup_table_size", lookup_table_size); + node->get_parameter(name + ".lookup_table_size", _lookup_table_size); nav2_util::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); - MotionModel motion_model = fromString(motion_model_for_search); - if (motion_model == MotionModel::UNKNOWN) { + node->get_parameter(name + ".motion_model_for_search", _motion_model_for_search); + _motion_model = fromString(_motion_model_for_search); + if (_motion_model == MotionModel::UNKNOWN) { RCLCPP_WARN( _logger, "Unable to get MotionModel search type. Given '%s', " "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP, STATE_LATTICE.", - motion_model_for_search.c_str()); + _motion_model_for_search.c_str()); } - if (max_iterations <= 0) { + if (_max_iterations <= 0) { RCLCPP_INFO( _logger, "maximum iteration selected as <= 0, " "disabling maximum iterations."); - max_iterations = std::numeric_limits::max(); + _max_iterations = std::numeric_limits::max(); } // convert to grid coordinates - const double minimum_turning_radius_global_coords = search_info.minimum_turning_radius; - search_info.minimum_turning_radius = - search_info.minimum_turning_radius / (_costmap->getResolution() * _downsampling_factor); - float lookup_table_dim = - static_cast(lookup_table_size) / + const double minimum_turning_radius_global_coords = _search_info.minimum_turning_radius; + _search_info.minimum_turning_radius = + _search_info.minimum_turning_radius / (_costmap->getResolution() * _downsampling_factor); + _lookup_table_dim = + static_cast(_lookup_table_size) / static_cast(_costmap->getResolution() * _downsampling_factor); // Make sure its a whole number - lookup_table_dim = static_cast(static_cast(lookup_table_dim)); + _lookup_table_dim = static_cast(static_cast(_lookup_table_dim)); // Make sure its an odd number - if (static_cast(lookup_table_dim) % 2 == 0) { + if (static_cast(_lookup_table_dim) % 2 == 0) { RCLCPP_INFO( _logger, "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd", - lookup_table_dim); - lookup_table_dim += 1.0; + _lookup_table_dim); + _lookup_table_dim += 1.0; } // Initialize collision checker _collision_checker = GridCollisionChecker(_costmap, _angle_quantizations); _collision_checker.setFootprint( - costmap_ros->getRobotFootprint(), - costmap_ros->getUseRadius(), - findCircumscribedCost(costmap_ros)); + _costmap_ros->getRobotFootprint(), + _costmap_ros->getUseRadius(), + findCircumscribedCost(_costmap_ros)); // Initialize A* template - _a_star = std::make_unique>(motion_model, search_info); + _a_star = std::make_unique>(_motion_model, _search_info); _a_star->initialize( - allow_unknown, - max_iterations, + _allow_unknown, + _max_iterations, std::numeric_limits::max(), - lookup_table_dim, + _lookup_table_dim, _angle_quantizations); // Initialize path smoother @@ -176,20 +175,30 @@ void SmacPlannerHybrid::configure( // Initialize costmap downsampler if (_downsample_costmap && _downsampling_factor > 1) { - std::string topic_name = "downsampled_costmap"; _costmap_downsampler = std::make_unique(); + std::string topic_name = "downsampled_costmap"; _costmap_downsampler->on_configure( node, _global_frame, topic_name, _costmap, _downsampling_factor); } _raw_plan_publisher = node->create_publisher("unsmoothed_plan", 1); + // Setup callback for changes to parameters. + _parameters_client = std::make_shared( + node->get_node_base_interface(), + node->get_node_topics_interface(), + node->get_node_graph_interface(), + node->get_node_services_interface()); + + _parameter_event_sub = _parameters_client->on_parameter_event( + std::bind(&SmacPlannerHybrid::on_parameter_event_callback, this, _1)); + RCLCPP_INFO( _logger, "Configured plugin %s of type SmacPlannerHybrid with " "maximum iterations %i, and %s. Using motion model: %s.", - _name.c_str(), max_iterations, - allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal", - toString(motion_model).c_str()); + _name.c_str(), _max_iterations, + _allow_unknown ? "allowing unknown traversal" : "not allowing unknown traversal", + toString(_motion_model).c_str()); } void SmacPlannerHybrid::activate() @@ -232,6 +241,7 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( const geometry_msgs::msg::PoseStamped & start, const geometry_msgs::msg::PoseStamped & goal) { + std::lock_guard lock_reinit(_mutex); steady_clock::time_point a = steady_clock::now(); std::unique_lock lock(*(_costmap->getMutex())); @@ -340,6 +350,158 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan( return plan; } +void SmacPlannerHybrid::on_parameter_event_callback( + const rcl_interfaces::msg::ParameterEvent::SharedPtr event) +{ + std::lock_guard lock_reinit(_mutex); + + bool reinit_collision_checker = false; + bool reinit_a_star = false; + bool reinit_downsampler = false; + bool reinit_smoother = false; + + for (auto & changed_parameter : event->changed_parameters) { + const auto & type = changed_parameter.value.type; + const auto & name = changed_parameter.name; + const auto & value = changed_parameter.value; + + if (type == ParameterType::PARAMETER_DOUBLE) { + if (name == _name + ".max_planning_time") { + _max_planning_time = value.double_value; + } else if (name == _name + ".lookup_table_size") { + reinit_a_star = true; + _lookup_table_size = value.double_value; + } else if (name == _name + ".minimum_turning_radius") { + reinit_a_star = true; + reinit_smoother = true; + _search_info.minimum_turning_radius = static_cast(value.double_value); + } else if (name == _name + ".reverse_penalty") { + reinit_a_star = true; + _search_info.reverse_penalty = static_cast(value.double_value); + } else if (name == _name + ".change_penalty") { + reinit_a_star = true; + _search_info.change_penalty = static_cast(value.double_value); + } else if (name == _name + ".non_straight_penalty") { + reinit_a_star = true; + _search_info.non_straight_penalty = static_cast(value.double_value); + } else if (name == _name + ".cost_penalty") { + reinit_a_star = true; + _search_info.cost_penalty = static_cast(value.double_value); + } else if (name == _name + ".analytic_expansion_ratio") { + reinit_a_star = true; + _search_info.analytic_expansion_ratio = static_cast(value.double_value); + } + } else if (type == ParameterType::PARAMETER_BOOL) { + if (name == _name + ".downsample_costmap") { + reinit_downsampler = true; + _downsample_costmap = value.bool_value; + } else if (name == _name + ".allow_unknown") { + reinit_a_star = true; + _allow_unknown = value.bool_value; + } else if (name == _name + ".cache_obstacle_heuristic") { + reinit_a_star = true; + _search_info.cache_obstacle_heuristic = value.bool_value; + } + } else if (type == ParameterType::PARAMETER_INTEGER) { + if (name == _name + ".downsampling_factor") { + reinit_a_star = true; + reinit_downsampler = true; + _downsampling_factor = value.integer_value; + } else if (name == _name + ".max_iterations") { + reinit_a_star = true; + _max_iterations = value.integer_value; + if (_max_iterations <= 0) { + RCLCPP_INFO( + _logger, "maximum iteration selected as <= 0, " + "disabling maximum iterations."); + _max_iterations = std::numeric_limits::max(); + } + } else if (name == _name + ".angle_quantization_bins") { + reinit_collision_checker = true; + reinit_a_star = true; + int angle_quantizations = value.integer_value; + _angle_bin_size = 2.0 * M_PI / angle_quantizations; + _angle_quantizations = static_cast(angle_quantizations); + } + } else if (type == ParameterType::PARAMETER_STRING) { + if (name == _name + ".motion_model_for_search") { + reinit_a_star = true; + _motion_model = fromString(value.string_value); + if (_motion_model == MotionModel::UNKNOWN) { + RCLCPP_WARN( + _logger, + "Unable to get MotionModel search type. Given '%s', " + "valid options are MOORE, VON_NEUMANN, DUBIN, REEDS_SHEPP.", + _motion_model_for_search.c_str()); + } + } + } + } + + // Re-init if needed with mutex lock (to avoid re-init while creating a plan) + if (reinit_a_star || reinit_downsampler || reinit_collision_checker || reinit_smoother) { + // convert to grid coordinates + const double minimum_turning_radius_global_coords = _search_info.minimum_turning_radius; + _search_info.minimum_turning_radius = + _search_info.minimum_turning_radius / (_costmap->getResolution() * _downsampling_factor); + _lookup_table_dim = + static_cast(_lookup_table_size) / + static_cast(_costmap->getResolution() * _downsampling_factor); + + // Make sure its a whole number + _lookup_table_dim = static_cast(static_cast(_lookup_table_dim)); + + // Make sure its an odd number + if (static_cast(_lookup_table_dim) % 2 == 0) { + RCLCPP_INFO( + _logger, + "Even sized heuristic lookup table size set %f, increasing size by 1 to make odd", + _lookup_table_dim); + _lookup_table_dim += 1.0; + } + + // Re-Initialize A* template + if (reinit_a_star) { + _a_star = std::make_unique>(_motion_model, _search_info); + _a_star->initialize( + _allow_unknown, + _max_iterations, + std::numeric_limits::max(), + _lookup_table_dim, + _angle_quantizations); + } + + // Re-Initialize costmap downsampler + if (reinit_downsampler) { + if (_downsample_costmap && _downsampling_factor > 1) { + auto node = _node.lock(); + std::string topic_name = "downsampled_costmap"; + _costmap_downsampler = std::make_unique(); + _costmap_downsampler->on_configure( + node, _global_frame, topic_name, _costmap, _downsampling_factor); + } + } + + // Re-Initialize collision checker + if (reinit_collision_checker) { + _collision_checker = GridCollisionChecker(_costmap, _angle_quantizations); + _collision_checker.setFootprint( + _costmap_ros->getRobotFootprint(), + _costmap_ros->getUseRadius(), + findCircumscribedCost(_costmap_ros)); + } + + // Re-Initialize smoother + if (reinit_smoother) { + auto node = _node.lock(); + SmootherParams params; + params.get(node, _name); + _smoother = std::make_unique(params); + _smoother->initialize(minimum_turning_radius_global_coords); + } + } +} + } // namespace nav2_smac_planner #include "pluginlib/class_list_macros.hpp" diff --git a/nav2_smac_planner/test/test_smac_hybrid.cpp b/nav2_smac_planner/test/test_smac_hybrid.cpp index 9c6d50a0b5..f09139055e 100644 --- a/nav2_smac_planner/test/test_smac_hybrid.cpp +++ b/nav2_smac_planner/test/test_smac_hybrid.cpp @@ -79,3 +79,61 @@ TEST(SmacTest, test_smac_se2) costmap_ros.reset(); nodeSE2.reset(); } + +TEST(SmacTest, test_smac_se2_reconfigure) +{ + rclcpp_lifecycle::LifecycleNode::SharedPtr nodeSE2 = + std::make_shared("SmacSE2Test"); + + std::shared_ptr costmap_ros = + std::make_shared("global_costmap"); + costmap_ros->on_configure(rclcpp_lifecycle::State()); + + auto planner = std::make_unique(); + planner->configure(nodeSE2, "test", nullptr, costmap_ros); + planner->activate(); + + auto rec_param = std::make_shared( + nodeSE2->get_node_base_interface(), nodeSE2->get_node_topics_interface(), + nodeSE2->get_node_graph_interface(), + nodeSE2->get_node_services_interface()); + + auto results = rec_param->set_parameters_atomically( + {rclcpp::Parameter("test.downsample_costmap", true), + rclcpp::Parameter("test.downsampling_factor", 2), + rclcpp::Parameter("test.angle_quantization_bins", 100), + rclcpp::Parameter("test.allow_unknown", false), + rclcpp::Parameter("test.max_iterations", -1), + rclcpp::Parameter("test.minimum_turning_radius", 1.0), + rclcpp::Parameter("test.cache_obstacle_heuristic", true), + rclcpp::Parameter("test.reverse_penalty", 5.0), + rclcpp::Parameter("test.change_penalty", 1.0), + rclcpp::Parameter("test.non_straight_penalty", 2.0), + rclcpp::Parameter("test.cost_penalty", 2.0), + rclcpp::Parameter("test.analytic_expansion_ratio", 4.0), + rclcpp::Parameter("test.max_planning_time", 10.0), + rclcpp::Parameter("test.lookup_table_size", 30.0), + rclcpp::Parameter("test.motion_model_for_search", std::string("REEDS_SHEPP"))}); + + rclcpp::spin_until_future_complete( + nodeSE2->get_node_base_interface(), + results); + + EXPECT_EQ(nodeSE2->get_parameter("test.downsample_costmap").as_bool(), true); + EXPECT_EQ(nodeSE2->get_parameter("test.downsampling_factor").as_int(), 2); + EXPECT_EQ(nodeSE2->get_parameter("test.angle_quantization_bins").as_int(), 100); + EXPECT_EQ(nodeSE2->get_parameter("test.allow_unknown").as_bool(), false); + EXPECT_EQ(nodeSE2->get_parameter("test.max_iterations").as_int(), -1); + EXPECT_EQ(nodeSE2->get_parameter("test.minimum_turning_radius").as_double(), 1.0); + EXPECT_EQ(nodeSE2->get_parameter("test.cache_obstacle_heuristic").as_bool(), true); + EXPECT_EQ(nodeSE2->get_parameter("test.reverse_penalty").as_double(), 5.0); + EXPECT_EQ(nodeSE2->get_parameter("test.change_penalty").as_double(), 1.0); + EXPECT_EQ(nodeSE2->get_parameter("test.non_straight_penalty").as_double(), 2.0); + EXPECT_EQ(nodeSE2->get_parameter("test.cost_penalty").as_double(), 2.0); + EXPECT_EQ(nodeSE2->get_parameter("test.analytic_expansion_ratio").as_double(), 4.0); + EXPECT_EQ(nodeSE2->get_parameter("test.max_planning_time").as_double(), 10.0); + EXPECT_EQ(nodeSE2->get_parameter("test.lookup_table_size").as_double(), 30.0); + EXPECT_EQ( + nodeSE2->get_parameter("test.motion_model_for_search").as_string(), + std::string("REEDS_SHEPP")); +}