Skip to content
Snippets Groups Projects
Commit 6b3088dd authored by bpwilcox's avatar bpwilcox
Browse files

declare parameters fix for server & plugin lifecycle reset and startup

parent d01308ee
No related branches found
No related tags found
No related merge requests found
...@@ -17,6 +17,7 @@ ...@@ -17,6 +17,7 @@
#include <memory> #include <memory>
#include "back_up.hpp" #include "back_up.hpp"
#include "nav2_util/node_utils.hpp"
using namespace std::chrono_literals; using namespace std::chrono_literals;
...@@ -26,7 +27,6 @@ namespace nav2_recoveries ...@@ -26,7 +27,6 @@ namespace nav2_recoveries
BackUp::BackUp() BackUp::BackUp()
: Recovery<BackUpAction>() : Recovery<BackUpAction>()
{ {
simulate_ahead_time_ = 2.0;
} }
BackUp::~BackUp() BackUp::~BackUp()
...@@ -35,8 +35,9 @@ BackUp::~BackUp() ...@@ -35,8 +35,9 @@ BackUp::~BackUp()
void BackUp::onConfigure() void BackUp::onConfigure()
{ {
node_->declare_parameter("simulate_ahead_time", simulate_ahead_time_); nav2_util::declare_parameter_if_not_declared(node_,
simulate_ahead_time_ = node_->get_parameter("simulate_ahead_time").as_double(); "simulate_ahead_time", rclcpp::ParameterValue(2.0));
node_->get_parameter("simulate_ahead_time", simulate_ahead_time_);
} }
Status BackUp::onRun(const std::shared_ptr<const BackUpAction::Goal> command) Status BackUp::onRun(const std::shared_ptr<const BackUpAction::Goal> command)
......
...@@ -25,6 +25,21 @@ RecoveryServer::RecoveryServer() ...@@ -25,6 +25,21 @@ RecoveryServer::RecoveryServer()
: nav2_util::LifecycleNode("nav2_recoveries", "", true), : nav2_util::LifecycleNode("nav2_recoveries", "", true),
plugin_loader_("nav2_core", "nav2_core::Recovery") plugin_loader_("nav2_core", "nav2_core::Recovery")
{ {
declare_parameter("costmap_topic",
rclcpp::ParameterValue(std::string("local_costmap/costmap_raw")));
declare_parameter("footprint_topic",
rclcpp::ParameterValue(std::string("local_costmap/published_footprint")));
std::vector<std::string> plugin_names{std::string("Spin"),
std::string("BackUp"), std::string("Wait")};
std::vector<std::string> plugin_types{std::string("nav2_recoveries/Spin"),
std::string("nav2_recoveries/BackUp"),
std::string("nav2_recoveries/Wait")};
declare_parameter("plugin_names",
rclcpp::ParameterValue(plugin_names));
declare_parameter("plugin_types",
rclcpp::ParameterValue(plugin_types));
} }
...@@ -44,24 +59,8 @@ RecoveryServer::on_configure(const rclcpp_lifecycle::State & /*state*/) ...@@ -44,24 +59,8 @@ RecoveryServer::on_configure(const rclcpp_lifecycle::State & /*state*/)
tf_->setCreateTimerInterface(timer_interface); tf_->setCreateTimerInterface(timer_interface);
transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_); transform_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_);
declare_parameter("costmap_topic", get_parameter("plugin_names", plugin_names_);
rclcpp::ParameterValue(std::string("local_costmap/costmap_raw"))); get_parameter("plugin_types", plugin_types_);
declare_parameter("footprint_topic",
rclcpp::ParameterValue(std::string("local_costmap/published_footprint")));
std::vector<std::string> plugin_names{std::string("Spin"),
std::string("BackUp"), std::string("Wait")};
std::vector<std::string> plugin_types{std::string("nav2_recoveries/Spin"),
std::string("nav2_recoveries/BackUp"),
std::string("nav2_recoveries/Wait")};
declare_parameter("plugin_names",
rclcpp::ParameterValue(plugin_names));
declare_parameter("plugin_types",
rclcpp::ParameterValue(plugin_types));
plugin_names_ = get_parameter("plugin_names").as_string_array();
plugin_types_ = get_parameter("plugin_types").as_string_array();
loadRecoveryPlugins(); loadRecoveryPlugins();
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment