Main Page
Namespaces
Namespace List
Namespace Members
All
Functions
Classes
Class List
Class Hierarchy
Class Members
All
a
c
d
e
g
h
i
l
m
n
o
p
r
s
t
u
v
~
Functions
a
c
d
g
h
i
l
n
o
p
r
s
t
~
Variables
c
d
e
g
i
l
m
n
p
s
t
u
v
Typedefs
Files
File List
File Members
All
Functions
src
backwards_compatibility.cpp
Go to the documentation of this file.
1
/*
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2017, Locus Robotics
5
* All rights reserved.
6
*
7
* Redistribution and use in source and binary forms, with or without
8
* modification, are permitted provided that the following conditions
9
* are met:
10
*
11
* * Redistributions of source code must retain the above copyright
12
* notice, this list of conditions and the following disclaimer.
13
* * Redistributions in binary form must reproduce the above
14
* copyright notice, this list of conditions and the following
15
* disclaimer in the documentation and/or other materials provided
16
* with the distribution.
17
* * Neither the name of the copyright holder nor the names of its
18
* contributors may be used to endorse or promote products derived
19
* from this software without specific prior written permission.
20
*
21
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25
* COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32
* POSSIBILITY OF SUCH DAMAGE.
33
*/
34
#include <
dwb_local_planner/backwards_compatibility.h
>
35
#include <
nav_2d_utils/parameters.h
>
36
#include <string>
37
#include <vector>
38
39
namespace
dwb_local_planner
40
{
41
42
using
nav_2d_utils::moveParameter
;
43
44
std::string
getBackwardsCompatibleDefaultGenerator
(
const
ros::NodeHandle
& nh)
45
{
46
bool
use_dwa;
47
nh.
param
(
"use_dwa"
, use_dwa,
true
);
48
if
(use_dwa)
49
{
50
return
"dwb_plugins::LimitedAccelGenerator"
;
51
}
52
else
53
{
54
return
"dwb_plugins::StandardTrajectoryGenerator"
;
55
}
56
}
57
58
void
loadBackwardsCompatibleParameters
(
const
ros::NodeHandle
& nh)
59
{
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"
);
// discards trajectories that move forward when already at goal
63
critic_names.push_back(
"Oscillation"
);
// discards oscillating motions (assisgns cost -1)
64
critic_names.push_back(
"ObstacleFootprint"
);
// discards trajectories that move into obstacles
65
critic_names.push_back(
"GoalAlign"
);
// prefers trajectories that make the nose go towards (local) nose goal
66
critic_names.push_back(
"PathAlign"
);
// prefers trajectories that keep the robot nose on nose path
67
critic_names.push_back(
"PathDist"
);
// prefers trajectories on global path
68
critic_names.push_back(
"GoalDist"
);
// prefers trajectories that go towards (local) goal,
69
// based on wave propagation
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);
76
77
moveParameter
(nh,
"max_scaling_factor"
,
"ObstacleFootprint/max_scaling_factor"
, 0.2);
78
moveParameter
(nh,
"scaling_speed"
,
"ObstacleFootprint/scaling_speed"
, 0.25);
79
}
80
81
}
// namespace dwb_local_planner
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
dwb_local_planner
Definition:
backwards_compatibility.h:40
ROS_INFO_NAMED
#define ROS_INFO_NAMED(name,...)
dwb_local_planner::loadBackwardsCompatibleParameters
void loadBackwardsCompatibleParameters(const ros::NodeHandle &nh)
Load parameters to emulate dwa_local_planner.
Definition:
backwards_compatibility.cpp:58
nav_2d_utils::moveParameter
void moveParameter(const ros::NodeHandle &nh, std::string old_name, std::string current_name, param_t default_value, bool should_delete=true)
parameters.h
ros::NodeHandle::param
T param(const std::string ¶m_name, const T &default_val) const
backwards_compatibility.h
ros::NodeHandle
dwb_local_planner::getBackwardsCompatibleDefaultGenerator
std::string getBackwardsCompatibleDefaultGenerator(const ros::NodeHandle &nh)
Definition:
backwards_compatibility.cpp:44
dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Sun Jul 3 2022 02:47:54