Skip to content
Snippets Groups Projects
Unverified Commit e49cb5ad authored by Wilco Bonestroo's avatar Wilco Bonestroo Committed by GitHub
Browse files

Remove code for DWA to DWB migration (#2027)

* Remove the parameters.hpp file.

* Put parameters.hpp back. Only removed the two functions for depricated parameters.

* Removed DWBLocalPlanner::loadBackwardsCompatibleParameters(). It will now throw a runtime error if there are no critics declared in the parameters.

* Remove moveParameter. It was not used anywhere.
parent f37ae148
No related branches found
No related tags found
No related merge requests found
......@@ -182,7 +182,6 @@ protected:
* @param name The namespace of this planner.
*/
virtual void loadCritics();
void loadBackwardsCompatibleParameters();
rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
rclcpp::Clock::SharedPtr clock_;
......
......@@ -180,7 +180,7 @@ DWBLocalPlanner::loadCritics()
std::vector<std::string> critic_names;
if (!node->get_parameter(dwb_plugin_name_ + ".critics", critic_names)) {
loadBackwardsCompatibleParameters();
throw std::runtime_error("No critics defined for " + dwb_plugin_name_);
}
node->get_parameter(dwb_plugin_name_ + ".critics", critic_names);
......@@ -210,64 +210,6 @@ DWBLocalPlanner::loadCritics()
}
}
void
DWBLocalPlanner::loadBackwardsCompatibleParameters()
{
std::vector<std::string> critic_names;
RCLCPP_INFO(
logger_,
"DWBLocalPlanner", "No critics configured! Using the default set.");
critic_names.emplace_back("RotateToGoal"); // discards trajectories that move forward when
// already at goal
critic_names.emplace_back("Oscillation"); // discards oscillating motions (assisgns cost -1)
critic_names.emplace_back("ObstacleFootprint"); // discards trajectories that move into obstacles
critic_names.emplace_back("GoalAlign"); // prefers trajectories that make the
// nose go towards (local) nose goal
critic_names.emplace_back("PathAlign"); // prefers trajectories that keep the
// robot nose on nose path
critic_names.emplace_back("PathDist"); // prefers trajectories on global path
critic_names.emplace_back("GoalDist"); // prefers trajectories that go towards
// (local) goal, based on wave propagation
auto node = node_.lock();
if (!node) {
throw std::runtime_error{"Failed to lock node"};
}
node->set_parameters({rclcpp::Parameter(dwb_plugin_name_ + ".critics", critic_names)});
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".path_distance_bias");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".goal_distance_bias");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".occdist_scale");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".max_scaling_factor");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".scaling_speed");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".PathAlign.scale");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".GoalAlign.scale");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".PathDist.scale");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".GoalDist.scale");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".ObstacleFootprint.scale");
declare_parameter_if_not_declared(
node, dwb_plugin_name_ + ".ObstacleFootprint.max_scaling_factor");
declare_parameter_if_not_declared(node, dwb_plugin_name_ + ".ObstacleFootprint.scaling_speed");
/* *INDENT-OFF* */
nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".path_distance_bias",
dwb_plugin_name_ + ".PathAlign.scale", 32.0, false);
nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".goal_distance_bias",
dwb_plugin_name_ + ".GoalAlign.scale", 24.0, false);
nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".path_distance_bias",
dwb_plugin_name_ + ".PathDist.scale", 32.0);
nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".goal_distance_bias",
dwb_plugin_name_ + ".GoalDist.scale", 24.0);
nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".occdist_scale",
dwb_plugin_name_ + ".ObstacleFootprint.scale", 0.01);
nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".max_scaling_factor",
dwb_plugin_name_ + ".ObstacleFootprint.max_scaling_factor", 0.2);
nav_2d_utils::moveParameter(node, dwb_plugin_name_ + ".scaling_speed",
dwb_plugin_name_ + ".ObstacleFootprint.scaling_speed", 0.25);
/* *INDENT-ON* */
}
void
DWBLocalPlanner::setPlan(const nav_msgs::msg::Path & path)
{
......
......@@ -41,7 +41,6 @@
#include "nav2_util/node_utils.hpp"
using nav2_util::declare_parameter_if_not_declared;
using nav_2d_utils::moveDeprecatedParameter;
using rcl_interfaces::msg::ParameterType;
using std::placeholders::_1;
......@@ -63,11 +62,6 @@ void KinematicsHandler::initialize(
const std::string & plugin_name)
{
plugin_name_ = plugin_name;
// Special handling for renamed parameters
moveDeprecatedParameter<double>(nh, plugin_name + ".max_vel_theta", "max_rot_vel");
moveDeprecatedParameter<double>(nh, plugin_name + ".min_speed_xy", "min_trans_vel");
moveDeprecatedParameter<double>(nh, plugin_name + ".max_speed_xy", "max_trans_vel");
moveDeprecatedParameter<double>(nh, plugin_name + ".min_speed_theta", "min_rot_vel");
declare_parameter_if_not_declared(nh, plugin_name + ".min_vel_x", rclcpp::ParameterValue(0.0));
declare_parameter_if_not_declared(nh, plugin_name + ".min_vel_y", rclcpp::ParameterValue(0.0));
......
......@@ -43,8 +43,6 @@
#include "dwb_core/exceptions.hpp"
#include "nav2_util/node_utils.hpp"
using nav_2d_utils::loadParameterWithDeprecation;
namespace dwb_plugins
{
......
......@@ -80,95 +80,6 @@ param_t searchAndGetParam(
return value;
}
/**
* @brief Load a parameter from one of two namespaces. Complain if it uses the old name.
* @param nh NodeHandle to look for the parameter in
* @param current_name Parameter name that is current, i.e. not deprecated
* @param old_name Deprecated parameter name
* @param default_value If neither parameter is present, return this value
* @return The value of the parameter or the default value
*/
template<class param_t>
param_t loadParameterWithDeprecation(
const nav2_util::LifecycleNode::SharedPtr & nh, const std::string current_name,
const std::string old_name, const param_t & default_value)
{
nav2_util::declare_parameter_if_not_declared(
nh, current_name, rclcpp::ParameterValue(default_value));
nav2_util::declare_parameter_if_not_declared(
nh, old_name, rclcpp::ParameterValue(default_value));
param_t current_name_value;
nh->get_parameter(current_name, current_name_value);
param_t old_name_value;
nh->get_parameter(old_name, old_name_value);
if (old_name_value != current_name_value && old_name_value != default_value) {
RCLCPP_WARN(
nh->get_logger(),
"Parameter %s is deprecated. Please use the name %s instead.",
old_name.c_str(), current_name.c_str());
// set both parameters to the same value
nh->set_parameters({rclcpp::Parameter(current_name, old_name_value)});
current_name_value = old_name_value;
}
return current_name_value;
}
/**
* @brief If a deprecated parameter exists, complain and move to its new location
* @param nh NodeHandle to look for the parameter in
* @param current_name Parameter name that is current, i.e. not deprecated
* @param old_name Deprecated parameter name
*/
template<class param_t>
void moveDeprecatedParameter(
const nav2_util::LifecycleNode::SharedPtr & nh, const std::string current_name,
const std::string old_name)
{
param_t value;
if (!nh->get_parameter(old_name, value)) {return;}
RCLCPP_WARN(
nh->get_logger(),
"Parameter %s is deprecated. Please use the name %s instead.",
old_name.c_str(), current_name.c_str());
nh->get_parameter(old_name, value);
nh->set_parameters({rclcpp::Parameter(current_name, value)});
}
/**
* @brief Move a parameter from one place to another
*
* For use loading old parameter structures into new places.
*
* If the new name already has a value, don't move the old value there.
*
* @param nh NodeHandle for loading/saving params
* @param old_name Parameter name to move/remove
* @param current_name Destination parameter name
* @param default_value Value to save in the new name if old parameter is not found.
* @param should_delete If true, whether to delete the parameter from the old name
*/
template<class param_t>
void moveParameter(
const nav2_util::LifecycleNode::SharedPtr & nh, std::string old_name,
std::string current_name, param_t default_value, bool should_delete = true)
{
param_t value = 0;
if (nh->get_parameter(current_name, value)) {
if (should_delete) {nh->undeclare_parameter(old_name);}
return;
}
if (nh->get_parameter(old_name, value)) {
if (should_delete) {nh->undeclare_parameter(old_name);}
} else {
value = default_value;
}
nh->set_parameter(rclcpp::Parameter(current_name, value));
}
} // namespace nav_2d_utils
#pragma GCC diagnostic pop
......
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