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

integrate declare if not declared parameters through dwb

parent 0e1e7653
No related branches found
No related tags found
No related merge requests found
Showing
with 107 additions and 73 deletions
...@@ -38,9 +38,6 @@ ClearCostmapService::ClearCostmapService( ...@@ -38,9 +38,6 @@ ClearCostmapService::ClearCostmapService(
{ {
reset_value_ = costmap_.getCostmap()->getDefaultValue(); reset_value_ = costmap_.getCostmap()->getDefaultValue();
std::vector<std::string> clearable_layers{"obstacle_layer"};
node_->declare_parameter("clearable_layers", rclcpp::ParameterValue(clearable_layers));
node_->get_parameter("clearable_layers", clearable_layers_); node_->get_parameter("clearable_layers", clearable_layers_);
clear_except_service_ = node_->create_service<ClearExceptRegion>( clear_except_service_ = node_->create_service<ClearExceptRegion>(
......
...@@ -70,6 +70,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, const std::string & absolut ...@@ -70,6 +70,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, const std::string & absolut
std::vector<std::string> plugin_names{"static_layer", "obstacle_layer", "inflation_layer"}; std::vector<std::string> plugin_names{"static_layer", "obstacle_layer", "inflation_layer"};
std::vector<std::string> plugin_types{"nav2_costmap_2d::StaticLayer", std::vector<std::string> plugin_types{"nav2_costmap_2d::StaticLayer",
"nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"}; "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"};
std::vector<std::string> clearable_layers{"obstacle_layer"};
declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false)); declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f)); declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
...@@ -95,6 +96,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, const std::string & absolut ...@@ -95,6 +96,7 @@ Costmap2DROS::Costmap2DROS(const std::string & name, const std::string & absolut
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0)); declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
declare_parameter("use_maximum", rclcpp::ParameterValue(false)); declare_parameter("use_maximum", rclcpp::ParameterValue(false));
declare_parameter("width", rclcpp::ParameterValue(10)); declare_parameter("width", rclcpp::ParameterValue(10));
declare_parameter("clearable_layers", rclcpp::ParameterValue(clearable_layers));
} }
Costmap2DROS::~Costmap2DROS() Costmap2DROS::~Costmap2DROS()
......
...@@ -76,7 +76,7 @@ DwbController::on_configure(const rclcpp_lifecycle::State & state) ...@@ -76,7 +76,7 @@ DwbController::on_configure(const rclcpp_lifecycle::State & state)
get_parameter("controller_frequency", controller_frequency_); get_parameter("controller_frequency", controller_frequency_);
RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_); RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(*this); odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(node);
vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 1); vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 1);
// Create the action server that we implement with our followPath method // Create the action server that we implement with our followPath method
......
...@@ -47,8 +47,11 @@ ...@@ -47,8 +47,11 @@
#include "nav_2d_utils/parameters.hpp" #include "nav_2d_utils/parameters.hpp"
#include "nav_2d_utils/tf_help.hpp" #include "nav_2d_utils/tf_help.hpp"
#include "nav2_util/lifecycle_node.hpp" #include "nav2_util/lifecycle_node.hpp"
#include "nav2_util/node_utils.hpp"
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
using nav2_util::declare_parameter_if_not_declared;
namespace dwb_core namespace dwb_core
{ {
...@@ -62,16 +65,17 @@ DWBLocalPlanner::DWBLocalPlanner( ...@@ -62,16 +65,17 @@ DWBLocalPlanner::DWBLocalPlanner(
goal_checker_loader_("dwb_core", "dwb_core::GoalChecker"), goal_checker_loader_("dwb_core", "dwb_core::GoalChecker"),
critic_loader_("dwb_core", "dwb_core::TrajectoryCritic") critic_loader_("dwb_core", "dwb_core::TrajectoryCritic")
{ {
node_->declare_parameter("critics"); declare_parameter_if_not_declared(node_, "critics");
node_->declare_parameter("prune_plan", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared(node_, "prune_plan", rclcpp::ParameterValue(true));
node_->declare_parameter("prune_distance", rclcpp::ParameterValue(1.0)); declare_parameter_if_not_declared(node_, "prune_distance", rclcpp::ParameterValue(1.0));
node_->declare_parameter("debug_trajectory_details", rclcpp::ParameterValue(false)); declare_parameter_if_not_declared(node_, "debug_trajectory_details",
node_->declare_parameter("trajectory_generator_name", rclcpp::ParameterValue(false));
declare_parameter_if_not_declared(node_, "trajectory_generator_name",
rclcpp::ParameterValue(std::string("dwb_plugins::StandardTrajectoryGenerator"))); rclcpp::ParameterValue(std::string("dwb_plugins::StandardTrajectoryGenerator")));
node_->declare_parameter("goal_checker_name", declare_parameter_if_not_declared(node_, "goal_checker_name",
rclcpp::ParameterValue(std::string("dwb_plugins::SimpleGoalChecker"))); rclcpp::ParameterValue(std::string("dwb_plugins::SimpleGoalChecker")));
node_->declare_parameter("use_dwa", rclcpp::ParameterValue(false)); declare_parameter_if_not_declared(node_, "use_dwa", rclcpp::ParameterValue(false));
node_->declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1)); declare_parameter_if_not_declared(node_, "transform_tolerance", rclcpp::ParameterValue(0.1));
} }
nav2_util::CallbackReturn nav2_util::CallbackReturn
...@@ -173,7 +177,8 @@ DWBLocalPlanner::loadCritics() ...@@ -173,7 +177,8 @@ DWBLocalPlanner::loadCritics()
std::string plugin_name = critic_names[i]; std::string plugin_name = critic_names[i];
std::string plugin_class; std::string plugin_class;
node_->declare_parameter(plugin_name + "/class", rclcpp::ParameterValue(plugin_name)); declare_parameter_if_not_declared(node_, plugin_name + "/class",
rclcpp::ParameterValue(plugin_name));
node_->get_parameter(plugin_name + "/class", plugin_class); node_->get_parameter(plugin_name + "/class", plugin_class);
plugin_class = resolveCriticClassName(plugin_class); plugin_class = resolveCriticClassName(plugin_class);
...@@ -211,18 +216,18 @@ DWBLocalPlanner::loadBackwardsCompatibleParameters() ...@@ -211,18 +216,18 @@ DWBLocalPlanner::loadBackwardsCompatibleParameters()
// (local) goal, based on wave propagation // (local) goal, based on wave propagation
node_->set_parameters({rclcpp::Parameter("critics", critic_names)}); node_->set_parameters({rclcpp::Parameter("critics", critic_names)});
node_->declare_parameter("path_distance_bias"); declare_parameter_if_not_declared(node_, "path_distance_bias");
node_->declare_parameter("goal_distance_bias"); declare_parameter_if_not_declared(node_, "goal_distance_bias");
node_->declare_parameter("occdist_scale"); declare_parameter_if_not_declared(node_, "occdist_scale");
node_->declare_parameter("max_scaling_factor"); declare_parameter_if_not_declared(node_, "max_scaling_factor");
node_->declare_parameter("scaling_speed"); declare_parameter_if_not_declared(node_, "scaling_speed");
node_->declare_parameter("PathAlign.scale"); declare_parameter_if_not_declared(node_, "PathAlign.scale");
node_->declare_parameter("GoalAlign.scale"); declare_parameter_if_not_declared(node_, "GoalAlign.scale");
node_->declare_parameter("PathDist.scale"); declare_parameter_if_not_declared(node_, "PathDist.scale");
node_->declare_parameter("GoalDist.scale"); declare_parameter_if_not_declared(node_, "GoalDist.scale");
node_->declare_parameter("ObstacleFootprint.scale"); declare_parameter_if_not_declared(node_, "ObstacleFootprint.scale");
node_->declare_parameter("ObstacleFootprint.max_scaling_factor"); declare_parameter_if_not_declared(node_, "ObstacleFootprint.max_scaling_factor");
node_->declare_parameter("ObstacleFootprint.scaling_speed"); declare_parameter_if_not_declared(node_, "ObstacleFootprint.scaling_speed");
/* *INDENT-OFF* */ /* *INDENT-OFF* */
nav_2d_utils::moveParameter(node_, "path_distance_bias", "PathAlign.scale", 32.0, false); nav_2d_utils::moveParameter(node_, "path_distance_bias", "PathAlign.scale", 32.0, false);
......
...@@ -40,12 +40,14 @@ ...@@ -40,12 +40,14 @@
#include <vector> #include <vector>
#include "nav_2d_utils/conversions.hpp" #include "nav_2d_utils/conversions.hpp"
#include "nav2_util/node_utils.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp" #include "sensor_msgs/msg/point_cloud2.hpp"
#include "visualization_msgs/msg/marker_array.hpp" #include "visualization_msgs/msg/marker_array.hpp"
#include "visualization_msgs/msg/marker.hpp" #include "visualization_msgs/msg/marker.hpp"
using std::max; using std::max;
using std::string; using std::string;
using nav2_util::declare_parameter_if_not_declared;
namespace dwb_core namespace dwb_core
{ {
...@@ -53,12 +55,13 @@ namespace dwb_core ...@@ -53,12 +55,13 @@ namespace dwb_core
DWBPublisher::DWBPublisher(nav2_util::LifecycleNode::SharedPtr node) DWBPublisher::DWBPublisher(nav2_util::LifecycleNode::SharedPtr node)
: node_(node) : node_(node)
{ {
node_->declare_parameter("publish_evaluation", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared(node_, "publish_evaluation", rclcpp::ParameterValue(true));
node_->declare_parameter("publish_global_plan", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared(node_, "publish_global_plan", rclcpp::ParameterValue(true));
node_->declare_parameter("publish_transformed_plan", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared(node_, "publish_transformed_plan",
node_->declare_parameter("publish_local_plan", rclcpp::ParameterValue(true)); rclcpp::ParameterValue(true));
node_->declare_parameter("publish_trajectories", rclcpp::ParameterValue(true)); declare_parameter_if_not_declared(node_, "publish_local_plan", rclcpp::ParameterValue(true));
node_->declare_parameter("publish_cost_grid_pc", rclcpp::ParameterValue(false)); declare_parameter_if_not_declared(node_, "publish_trajectories", rclcpp::ParameterValue(true));
declare_parameter_if_not_declared(node_, "publish_cost_grid_pc", rclcpp::ParameterValue(false));
} }
nav2_util::CallbackReturn nav2_util::CallbackReturn
......
...@@ -36,6 +36,7 @@ ...@@ -36,6 +36,7 @@
#include "dwb_core/exceptions.hpp" #include "dwb_core/exceptions.hpp"
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
#include "nav2_costmap_2d/cost_values.hpp" #include "nav2_costmap_2d/cost_values.hpp"
#include "nav2_util/node_utils.hpp"
PLUGINLIB_EXPORT_CLASS(dwb_critics::BaseObstacleCritic, dwb_core::TrajectoryCritic) PLUGINLIB_EXPORT_CLASS(dwb_critics::BaseObstacleCritic, dwb_core::TrajectoryCritic)
...@@ -46,7 +47,8 @@ void BaseObstacleCritic::onInit() ...@@ -46,7 +47,8 @@ void BaseObstacleCritic::onInit()
{ {
costmap_ = costmap_ros_->getCostmap(); costmap_ = costmap_ros_->getCostmap();
nh_->declare_parameter(name_ + ".sum_scores", rclcpp::ParameterValue(false)); nav2_util::declare_parameter_if_not_declared(nh_,
name_ + ".sum_scores", rclcpp::ParameterValue(false));
nh_->get_parameter(name_ + ".sum_scores", sum_scores_); nh_->get_parameter(name_ + ".sum_scores", sum_scores_);
} }
......
...@@ -39,6 +39,7 @@ ...@@ -39,6 +39,7 @@
#include <memory> #include <memory>
#include "dwb_core/exceptions.hpp" #include "dwb_core/exceptions.hpp"
#include "nav2_costmap_2d/cost_values.hpp" #include "nav2_costmap_2d/cost_values.hpp"
#include "nav2_util/node_utils.hpp"
using std::abs; using std::abs;
using costmap_queue::CellData; using costmap_queue::CellData;
...@@ -60,7 +61,8 @@ void MapGridCritic::onInit() ...@@ -60,7 +61,8 @@ void MapGridCritic::onInit()
// Always set to true, but can be overriden by subclasses // Always set to true, but can be overriden by subclasses
stop_on_failure_ = true; stop_on_failure_ = true;
nh_->declare_parameter(name_ + ".aggregation_type", rclcpp::ParameterValue(std::string("last"))); nav2_util::declare_parameter_if_not_declared(nh_,
name_ + ".aggregation_type", rclcpp::ParameterValue(std::string("last")));
std::string aggro_str; std::string aggro_str;
nh_->get_parameter(name_ + ".aggregation_type", aggro_str); nh_->get_parameter(name_ + ".aggregation_type", aggro_str);
......
...@@ -38,6 +38,7 @@ ...@@ -38,6 +38,7 @@
#include <string> #include <string>
#include <vector> #include <vector>
#include "nav_2d_utils/parameters.hpp" #include "nav_2d_utils/parameters.hpp"
#include "nav2_util/node_utils.hpp"
#include "dwb_core/exceptions.hpp" #include "dwb_core/exceptions.hpp"
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
...@@ -96,7 +97,8 @@ void OscillationCritic::onInit() ...@@ -96,7 +97,8 @@ void OscillationCritic::onInit()
oscillation_reset_time_ = rclcpp::Duration::from_seconds( oscillation_reset_time_ = rclcpp::Duration::from_seconds(
nav_2d_utils::searchAndGetParam(nh_, "oscillation_reset_time", -1.0)); nav_2d_utils::searchAndGetParam(nh_, "oscillation_reset_time", -1.0));
nh_->declare_parameter(name_ + ".x_only_threshold", rclcpp::ParameterValue(0.05)); nav2_util::declare_parameter_if_not_declared(nh_,
name_ + ".x_only_threshold", rclcpp::ParameterValue(0.05));
/** /**
* Historical Parameter Loading * Historical Parameter Loading
......
...@@ -35,18 +35,21 @@ ...@@ -35,18 +35,21 @@
#include "dwb_critics/prefer_forward.hpp" #include "dwb_critics/prefer_forward.hpp"
#include <math.h> #include <math.h>
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
#include "nav2_util/node_utils.hpp"
PLUGINLIB_EXPORT_CLASS(dwb_critics::PreferForwardCritic, dwb_core::TrajectoryCritic) PLUGINLIB_EXPORT_CLASS(dwb_critics::PreferForwardCritic, dwb_core::TrajectoryCritic)
using nav2_util::declare_parameter_if_not_declared;
namespace dwb_critics namespace dwb_critics
{ {
void PreferForwardCritic::onInit() void PreferForwardCritic::onInit()
{ {
nh_->declare_parameter(name_ + ".penalty", rclcpp::ParameterValue(1.0)); declare_parameter_if_not_declared(nh_, name_ + ".penalty", rclcpp::ParameterValue(1.0));
nh_->declare_parameter(name_ + ".strafe_x", rclcpp::ParameterValue(0.1)); declare_parameter_if_not_declared(nh_, name_ + ".strafe_x", rclcpp::ParameterValue(0.1));
nh_->declare_parameter(name_ + ".strafe_theta", rclcpp::ParameterValue(0.2)); declare_parameter_if_not_declared(nh_, name_ + ".strafe_theta", rclcpp::ParameterValue(0.2));
nh_->declare_parameter(name_ + ".theta_scale", rclcpp::ParameterValue(10.0)); declare_parameter_if_not_declared(nh_, name_ + ".theta_scale", rclcpp::ParameterValue(10.0));
nh_->get_parameter(name_ + ".penalty", penalty_); nh_->get_parameter(name_ + ".penalty", penalty_);
nh_->get_parameter(name_ + ".strafe_x", strafe_x_); nh_->get_parameter(name_ + ".strafe_x", strafe_x_);
......
...@@ -39,10 +39,12 @@ ...@@ -39,10 +39,12 @@
#include <string> #include <string>
#include "nav_2d_utils/parameters.hpp" #include "nav_2d_utils/parameters.hpp"
#include "nav2_util/node_utils.hpp"
using std::fabs; using std::fabs;
using nav2_util::declare_parameter_if_not_declared;
using nav_2d_utils::moveDeprecatedParameter; using nav_2d_utils::moveDeprecatedParameter;
namespace dwb_plugins namespace dwb_plugins
{ {
...@@ -58,20 +60,20 @@ void KinematicParameters::initialize(const nav2_util::LifecycleNode::SharedPtr & ...@@ -58,20 +60,20 @@ void KinematicParameters::initialize(const nav2_util::LifecycleNode::SharedPtr &
moveDeprecatedParameter<double>(nh, "max_speed_xy", "max_trans_vel"); moveDeprecatedParameter<double>(nh, "max_speed_xy", "max_trans_vel");
moveDeprecatedParameter<double>(nh, "min_speed_theta", "min_rot_vel"); moveDeprecatedParameter<double>(nh, "min_speed_theta", "min_rot_vel");
nh->declare_parameter("min_vel_x", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "min_vel_x", rclcpp::ParameterValue(0.0));
nh->declare_parameter("min_vel_y", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "min_vel_y", rclcpp::ParameterValue(0.0));
nh->declare_parameter("max_vel_x", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "max_vel_x", rclcpp::ParameterValue(0.0));
nh->declare_parameter("max_vel_y", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "max_vel_y", rclcpp::ParameterValue(0.0));
nh->declare_parameter("max_vel_theta", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "max_vel_theta", rclcpp::ParameterValue(0.0));
nh->declare_parameter("min_speed_xy", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "min_speed_xy", rclcpp::ParameterValue(0.0));
nh->declare_parameter("max_speed_xy", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "max_speed_xy", rclcpp::ParameterValue(0.0));
nh->declare_parameter("min_speed_theta", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "min_speed_theta", rclcpp::ParameterValue(0.0));
nh->declare_parameter("acc_lim_x", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "acc_lim_x", rclcpp::ParameterValue(0.0));
nh->declare_parameter("acc_lim_y", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "acc_lim_y", rclcpp::ParameterValue(0.0));
nh->declare_parameter("acc_lim_theta", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "acc_lim_theta", rclcpp::ParameterValue(0.0));
nh->declare_parameter("decel_lim_x", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "decel_lim_x", rclcpp::ParameterValue(0.0));
nh->declare_parameter("decel_lim_y", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "decel_lim_y", rclcpp::ParameterValue(0.0));
nh->declare_parameter("decel_lim_theta", rclcpp::ParameterValue(0.0)); declare_parameter_if_not_declared(nh, "decel_lim_theta", rclcpp::ParameterValue(0.0));
nh->get_parameter("min_vel_x", min_vel_x_); nh->get_parameter("min_vel_x", min_vel_x_);
nh->get_parameter("min_vel_y", min_vel_y_); nh->get_parameter("min_vel_y", min_vel_y_);
......
...@@ -38,6 +38,7 @@ ...@@ -38,6 +38,7 @@
#include "nav_2d_utils/parameters.hpp" #include "nav_2d_utils/parameters.hpp"
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
#include "dwb_core/exceptions.hpp" #include "dwb_core/exceptions.hpp"
#include "nav2_util/node_utils.hpp"
namespace dwb_plugins namespace dwb_plugins
{ {
...@@ -46,7 +47,7 @@ void LimitedAccelGenerator::initialize(const nav2_util::LifecycleNode::SharedPtr ...@@ -46,7 +47,7 @@ void LimitedAccelGenerator::initialize(const nav2_util::LifecycleNode::SharedPtr
{ {
StandardTrajectoryGenerator::initialize(nh); StandardTrajectoryGenerator::initialize(nh);
nh->declare_parameter("sim_period"); nav2_util::declare_parameter_if_not_declared(nh, "sim_period");
if (nh->get_parameter("sim_period", acceleration_time_)) { if (nh->get_parameter("sim_period", acceleration_time_)) {
} else { } else {
......
...@@ -36,6 +36,7 @@ ...@@ -36,6 +36,7 @@
#include <memory> #include <memory>
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
#include "angles/angles.h" #include "angles/angles.h"
#include "nav2_util/node_utils.hpp"
namespace dwb_plugins namespace dwb_plugins
{ {
...@@ -47,8 +48,10 @@ SimpleGoalChecker::SimpleGoalChecker() ...@@ -47,8 +48,10 @@ SimpleGoalChecker::SimpleGoalChecker()
void SimpleGoalChecker::initialize(const nav2_util::LifecycleNode::SharedPtr & nh) void SimpleGoalChecker::initialize(const nav2_util::LifecycleNode::SharedPtr & nh)
{ {
nh->declare_parameter("xy_goal_tolerance", rclcpp::ParameterValue(0.25)); nav2_util::declare_parameter_if_not_declared(nh,
nh->declare_parameter("yaw_goal_tolerance", rclcpp::ParameterValue(0.25)); "xy_goal_tolerance", rclcpp::ParameterValue(0.25));
nav2_util::declare_parameter_if_not_declared(nh,
"yaw_goal_tolerance", rclcpp::ParameterValue(0.25));
nh->get_parameter("xy_goal_tolerance", xy_goal_tolerance_); nh->get_parameter("xy_goal_tolerance", xy_goal_tolerance_);
nh->get_parameter("yaw_goal_tolerance", yaw_goal_tolerance_); nh->get_parameter("yaw_goal_tolerance", yaw_goal_tolerance_);
......
...@@ -41,6 +41,7 @@ ...@@ -41,6 +41,7 @@
#include "nav_2d_utils/parameters.hpp" #include "nav_2d_utils/parameters.hpp"
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
#include "dwb_core/exceptions.hpp" #include "dwb_core/exceptions.hpp"
#include "nav2_util/node_utils.hpp"
using nav_2d_utils::loadParameterWithDeprecation; using nav_2d_utils::loadParameterWithDeprecation;
...@@ -53,8 +54,9 @@ void StandardTrajectoryGenerator::initialize(const nav2_util::LifecycleNode::Sha ...@@ -53,8 +54,9 @@ void StandardTrajectoryGenerator::initialize(const nav2_util::LifecycleNode::Sha
kinematics_->initialize(nh); kinematics_->initialize(nh);
initializeIterator(nh); initializeIterator(nh);
nh->declare_parameter("sim_time", rclcpp::ParameterValue(1.7)); nav2_util::declare_parameter_if_not_declared(nh, "sim_time", rclcpp::ParameterValue(1.7));
nh->declare_parameter("discretize_by_time", rclcpp::ParameterValue(false)); nav2_util::declare_parameter_if_not_declared(nh,
"discretize_by_time", rclcpp::ParameterValue(false));
nh->get_parameter("sim_time", sim_time_); nh->get_parameter("sim_time", sim_time_);
checkUseDwaParam(nh); checkUseDwaParam(nh);
......
...@@ -36,6 +36,7 @@ ...@@ -36,6 +36,7 @@
#include <cmath> #include <cmath>
#include <memory> #include <memory>
#include "pluginlib/class_list_macros.hpp" #include "pluginlib/class_list_macros.hpp"
#include "nav2_util/node_utils.hpp"
using std::fabs; using std::fabs;
...@@ -51,8 +52,10 @@ void StoppedGoalChecker::initialize(const nav2_util::LifecycleNode::SharedPtr & ...@@ -51,8 +52,10 @@ void StoppedGoalChecker::initialize(const nav2_util::LifecycleNode::SharedPtr &
{ {
SimpleGoalChecker::initialize(nh); SimpleGoalChecker::initialize(nh);
nh->declare_parameter("rot_stopped_velocity", rclcpp::ParameterValue(0.25)); nav2_util::declare_parameter_if_not_declared(nh,
nh->declare_parameter("trans_stopped_velocity", rclcpp::ParameterValue(0.25)); "rot_stopped_velocity", rclcpp::ParameterValue(0.25));
nav2_util::declare_parameter_if_not_declared(nh,
"trans_stopped_velocity", rclcpp::ParameterValue(0.25));
nh->get_parameter("rot_stopped_velocity", rot_stopped_velocity_); nh->get_parameter("rot_stopped_velocity", rot_stopped_velocity_);
nh->get_parameter("trans_stopped_velocity", trans_stopped_velocity_); nh->get_parameter("trans_stopped_velocity", trans_stopped_velocity_);
......
...@@ -35,6 +35,7 @@ ...@@ -35,6 +35,7 @@
#include "dwb_plugins/xy_theta_iterator.hpp" #include "dwb_plugins/xy_theta_iterator.hpp"
#include <memory> #include <memory>
#include "nav_2d_utils/parameters.hpp" #include "nav_2d_utils/parameters.hpp"
#include "nav2_util/node_utils.hpp"
namespace dwb_plugins namespace dwb_plugins
{ {
...@@ -44,8 +45,8 @@ void XYThetaIterator::initialize( ...@@ -44,8 +45,8 @@ void XYThetaIterator::initialize(
{ {
kinematics_ = kinematics; kinematics_ = kinematics;
nh->declare_parameter("vx_samples", rclcpp::ParameterValue(20)); nav2_util::declare_parameter_if_not_declared(nh, "vx_samples", rclcpp::ParameterValue(20));
nh->declare_parameter("vy_samples", rclcpp::ParameterValue(5)); nav2_util::declare_parameter_if_not_declared(nh, "vy_samples", rclcpp::ParameterValue(5));
nh->get_parameter("vx_samples", vx_samples_); nh->get_parameter("vx_samples", vx_samples_);
nh->get_parameter("vy_samples", vy_samples_); nh->get_parameter("vy_samples", vy_samples_);
......
...@@ -43,6 +43,7 @@ ...@@ -43,6 +43,7 @@
#include "nav_msgs/msg/odometry.hpp" #include "nav_msgs/msg/odometry.hpp"
#include "nav2_util/lifecycle_node.hpp" #include "nav2_util/lifecycle_node.hpp"
#include "rclcpp/rclcpp.hpp" #include "rclcpp/rclcpp.hpp"
#include "nav2_util/node_utils.hpp"
namespace nav_2d_utils namespace nav_2d_utils
{ {
...@@ -60,22 +61,27 @@ public: ...@@ -60,22 +61,27 @@ public:
* @param nh NodeHandle for creating subscriber * @param nh NodeHandle for creating subscriber
* @param default_topic Name of the topic that will be loaded of the odom_topic param is not set. * @param default_topic Name of the topic that will be loaded of the odom_topic param is not set.
*/ */
explicit OdomSubscriber(nav2_util::LifecycleNode & nh, std::string default_topic = "odom") explicit OdomSubscriber(
nav2_util::LifecycleNode::SharedPtr & nh,
std::string default_topic = "odom")
{ {
std::string odom_topic; std::string odom_topic;
nh.get_parameter_or("odom_topic", odom_topic, default_topic); nh->get_parameter_or("odom_topic", odom_topic, default_topic);
odom_sub_ = odom_sub_ =
nh.create_subscription<nav_msgs::msg::Odometry>(odom_topic, nh->create_subscription<nav_msgs::msg::Odometry>(odom_topic,
rclcpp::SystemDefaultsQoS(), rclcpp::SystemDefaultsQoS(),
std::bind(&OdomSubscriber::odomCallback, this, std::placeholders::_1)); std::bind(&OdomSubscriber::odomCallback, this, std::placeholders::_1));
nh.declare_parameter("min_x_velocity_threshold", rclcpp::ParameterValue(0.0001)); nav2_util::declare_parameter_if_not_declared(nh,
nh.declare_parameter("min_y_velocity_threshold", rclcpp::ParameterValue(0.0001)); "min_x_velocity_threshold", rclcpp::ParameterValue(0.0001));
nh.declare_parameter("min_theta_velocity_threshold", rclcpp::ParameterValue(0.0001)); nav2_util::declare_parameter_if_not_declared(nh,
"min_y_velocity_threshold", rclcpp::ParameterValue(0.0001));
nav2_util::declare_parameter_if_not_declared(nh,
"min_theta_velocity_threshold", rclcpp::ParameterValue(0.0001));
nh.get_parameter("min_x_velocity_threshold", min_x_velocity_threshold_); nh->get_parameter("min_x_velocity_threshold", min_x_velocity_threshold_);
nh.get_parameter("min_y_velocity_threshold", min_y_velocity_threshold_); nh->get_parameter("min_y_velocity_threshold", min_y_velocity_threshold_);
nh.get_parameter("min_theta_velocity_threshold", min_theta_velocity_threshold_); nh->get_parameter("min_theta_velocity_threshold", min_theta_velocity_threshold_);
} }
inline nav_2d_msgs::msg::Twist2D getTwist() {return odom_vel_.velocity;} inline nav_2d_msgs::msg::Twist2D getTwist() {return odom_vel_.velocity;}
......
...@@ -84,11 +84,11 @@ template<typename NodeT> ...@@ -84,11 +84,11 @@ template<typename NodeT>
void declare_parameter_if_not_declared( void declare_parameter_if_not_declared(
NodeT node, NodeT node,
const std::string & param_name, const std::string & param_name,
const rclcpp::ParameterValue & default_value, const rclcpp::ParameterValue & default_value = rclcpp::ParameterValue(),
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor = const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor()) rcl_interfaces::msg::ParameterDescriptor())
{ {
if(!node->has_parameter(param_name)) { if (!node->has_parameter(param_name)) {
node->declare_parameter(param_name, default_value, parameter_descriptor); node->declare_parameter(param_name, default_value, parameter_descriptor);
} }
} }
......
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