47 nh.
param(
"use_dwa", use_dwa,
true);
50 return "dwb_plugins::LimitedAccelGenerator";
54 return "dwb_plugins::StandardTrajectoryGenerator";
60 std::vector<std::string> critic_names;
61 ROS_INFO_NAMED(
"DWBLocalPlanner",
"No critics configured! Using the default set.");
62 critic_names.push_back(
"RotateToGoal");
63 critic_names.push_back(
"Oscillation");
64 critic_names.push_back(
"ObstacleFootprint");
65 critic_names.push_back(
"GoalAlign");
66 critic_names.push_back(
"PathAlign");
67 critic_names.push_back(
"PathDist");
68 critic_names.push_back(
"GoalDist");
70 nh.
setParam(
"critics", critic_names);
71 moveParameter(nh,
"path_distance_bias",
"PathAlign/scale", 32.0,
false);
72 moveParameter(nh,
"goal_distance_bias",
"GoalAlign/scale", 24.0,
false);
73 moveParameter(nh,
"path_distance_bias",
"PathDist/scale", 32.0);
74 moveParameter(nh,
"goal_distance_bias",
"GoalDist/scale", 24.0);
75 moveParameter(nh,
"occdist_scale",
"ObstacleFootprint/scale", 0.01);
77 moveParameter(nh,
"max_scaling_factor",
"ObstacleFootprint/max_scaling_factor", 0.2);
78 moveParameter(nh,
"scaling_speed",
"ObstacleFootprint/scaling_speed", 0.25);
#define ROS_INFO_NAMED(name,...)
std::string getBackwardsCompatibleDefaultGenerator(const ros::NodeHandle &nh)
void loadBackwardsCompatibleParameters(const ros::NodeHandle &nh)
Load parameters to emulate dwa_local_planner.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void moveParameter(const ros::NodeHandle &nh, std::string old_name, std::string current_name, param_t default_value, bool should_delete=true)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const