Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
2
210910794
Manage
Activity
Members
Labels
Plan
Wiki
Code
Merge requests
0
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Deploy
Releases
Package Registry
Operate
Terraform modules
Analyze
Value stream analytics
Contributor analytics
Repository analytics
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Summer2021
210910794
Commits
6b3088dd
Commit
6b3088dd
authored
5 years ago
by
bpwilcox
Browse files
Options
Downloads
Patches
Plain Diff
declare parameters fix for server & plugin lifecycle reset and startup
parent
d01308ee
No related branches found
Branches containing commit
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
nav2_recoveries/plugins/back_up.cpp
+4
-3
4 additions, 3 deletions
nav2_recoveries/plugins/back_up.cpp
nav2_recoveries/src/recovery_server.cpp
+17
-18
17 additions, 18 deletions
nav2_recoveries/src/recovery_server.cpp
with
21 additions
and
21 deletions
nav2_recoveries/plugins/back_up.cpp
+
4
−
3
View file @
6b3088dd
...
...
@@ -17,6 +17,7 @@
#include
<memory>
#include
"back_up.hpp"
#include
"nav2_util/node_utils.hpp"
using
namespace
std
::
chrono_literals
;
...
...
@@ -26,7 +27,6 @@ namespace nav2_recoveries
BackUp
::
BackUp
()
:
Recovery
<
BackUpAction
>
()
{
simulate_ahead_time_
=
2.0
;
}
BackUp
::~
BackUp
()
...
...
@@ -35,8 +35,9 @@ BackUp::~BackUp()
void
BackUp
::
onConfigure
()
{
node_
->
declare_parameter
(
"simulate_ahead_time"
,
simulate_ahead_time_
);
simulate_ahead_time_
=
node_
->
get_parameter
(
"simulate_ahead_time"
).
as_double
();
nav2_util
::
declare_parameter_if_not_declared
(
node_
,
"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
)
...
...
This diff is collapsed.
Click to expand it.
nav2_recoveries/src/recovery_server.cpp
+
17
−
18
View file @
6b3088dd
...
...
@@ -25,6 +25,21 @@ RecoveryServer::RecoveryServer()
:
nav2_util
::
LifecycleNode
(
"nav2_recoveries"
,
""
,
true
),
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*/)
tf_
->
setCreateTimerInterface
(
timer_interface
);
transform_listener_
=
std
::
make_shared
<
tf2_ros
::
TransformListener
>
(
*
tf_
);
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
));
plugin_names_
=
get_parameter
(
"plugin_names"
).
as_string_array
();
plugin_types_
=
get_parameter
(
"plugin_types"
).
as_string_array
();
get_parameter
(
"plugin_names"
,
plugin_names_
);
get_parameter
(
"plugin_types"
,
plugin_types_
);
loadRecoveryPlugins
();
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment