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
f7c3ba46
Commit
f7c3ba46
authored
6 years ago
by
Brian
Committed by
bpwilcox
6 years ago
Browse files
Options
Downloads
Patches
Plain Diff
redesign for filtering dynamic parameters
parent
32627808
No related branches found
No related tags found
No related merge requests found
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
nav2_dynamic_params/include/nav2_dynamic_params/dynamic_params_client.hpp
+42
-28
42 additions, 28 deletions
...ams/include/nav2_dynamic_params/dynamic_params_client.hpp
nav2_dynamic_params/src/example_dynamic_params.cpp
+1
-0
1 addition, 0 deletions
nav2_dynamic_params/src/example_dynamic_params.cpp
with
43 additions
and
28 deletions
nav2_dynamic_params/include/nav2_dynamic_params/dynamic_params_client.hpp
+
42
−
28
View file @
f7c3ba46
...
...
@@ -33,12 +33,14 @@ public:
:
node_
(
node
)
{
add_parameter_clients
(
remote_names
);
init_parameters
();
parameters_client_for_callback_
=
std
::
make_shared
<
rclcpp
::
SyncParametersClient
>
(
node_
);
event_subscription_
=
parameters_client_for_callback_
->
on_parameter_event
(
std
::
bind
(
&
DynamicParamsClient
::
event_callback
,
this
,
std
::
placeholders
::
_1
));
}
~
DynamicParamsClient
()
{}
void
add_parameter_clients
(
std
::
vector
<
std
::
string
>
remote_names
=
{
""
}
)
void
add_parameter_clients
(
std
::
vector
<
std
::
string
>
remote_names
)
{
for
(
auto
&
name
:
remote_names
)
{
auto
client
=
std
::
make_shared
<
rclcpp
::
SyncParametersClient
>
(
node_
,
name
);
...
...
@@ -49,13 +51,12 @@ public:
void
set_callback
(
std
::
function
<
void
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
)
>
callback
)
{
for
(
auto
&
client
:
parameters_clients_
)
{
auto
sub
=
client
->
on_parameter_event
(
callback
);
event_subscriptions_
.
push_back
(
sub
);
}
user_callback_
=
callback
;
}
void
init
_parameters
(
const
std
::
vector
<
std
::
string
>
&
param_names
)
void
add
_parameters
(
const
std
::
vector
<
std
::
string
>
&
param_names
)
{
for
(
const
auto
&
client
:
parameters_clients_
)
{
auto
params
=
client
->
get_parameters
(
param_names
);
...
...
@@ -67,14 +68,14 @@ public:
}
}
void
init
_parameters
()
void
add
_parameters
()
{
std
::
vector
<
std
::
string
>
param_names
;
for
(
const
auto
&
client
:
parameters_clients_
)
{
auto
param_list
=
client
->
list_parameters
({},
1
);
param_names
.
insert
(
param_names
.
end
(),
param_list
.
names
.
begin
(),
param_list
.
names
.
end
());
}
init
_parameters
(
param_names
);
add
_parameters
(
param_names
);
}
std
::
vector
<
std
::
string
>
get_param_names
()
...
...
@@ -158,35 +159,48 @@ private:
}
}
void
add_params
(
std
::
string
remote_node
,
std
::
vector
<
std
::
string
>
param_names
){
void
event_callback
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
event
)
{
if
(
is_event_in_map
(
event
))
{
user_callback_
(
event
);
}
}
void
set_event_callback
(
std
::
string
remote_node
)
{
private
:
bool
is_event_in_map
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
event
)
{
// check that event variables exist in dynamic param map
// True if at least one parameter exists in parameter map
for
(
auto
&
new_parameter
:
event
->
new_parameters
)
{
if
(
dynamic_param_map_
.
count
(
new_parameter
.
name
))
{
return
true
;
}
}
std
::
function
<
void
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
)
>
callback
=
[
this
,
remote_node
](
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
event
)
->
void
{
if
(
check_event
(
event
,
remote_node
))
{
user_callback
(
event
,
remote_node
);
}
};
}
for
(
auto
&
changed_parameter
:
event
->
changed_parameters
)
{
if
(
dynamic_param_map_
.
count
(
changed_parameter
.
name
))
{
return
true
;
}
}
private
:
bool
check_event
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
event
,
std
::
string
remote_node
){
// grab parameter name
// check parameter name against list of dynamic parameters
for
(
auto
&
deleted_parameter
:
event
->
deleted_parameters
)
{
if
(
dynamic_param_map_
.
count
(
deleted_parameter
.
name
))
{
return
true
;
}
}
return
false
;
}
std
::
map
<
std
::
string
,
rclcpp
::
Parameter
>
dynamic_param_map_
;
std
::
vector
<
std
::
string
>
dynamic_param_names_
;
std
::
vector
<
rclcpp
::
SyncParametersClient
::
SharedPtr
>
parameters_clients_
;
rclcpp
::
SyncParametersClient
::
SharedPtr
parameters_client_for_callback_
;
rclcpp
::
Node
::
SharedPtr
node_
;
std
::
vector
<
rclcpp
::
Subscription
<
rcl_interfaces
::
msg
::
ParameterEvent
>::
SharedPtr
>
event_subscriptions_
;
rclcpp
::
Subscription
<
rcl_interfaces
::
msg
::
ParameterEvent
>::
SharedPtr
event_subscription_
;
std
::
function
<
void
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
,
std
::
string
node_name
)
>
user_callback
;
std
::
function
<
void
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
)
>
user_callback
_
;
};
}
// namespace nav2_dynamic_params
...
...
This diff is collapsed.
Click to expand it.
nav2_dynamic_params/src/example_dynamic_params.cpp
+
1
−
0
View file @
f7c3ba46
...
...
@@ -32,6 +32,7 @@ int main(int argc, char ** argv)
// Add Dynamic Reconfigure Client
dynamic_params_client
=
new
nav2_dynamic_params
::
DynamicParamsClient
(
node
);
dynamic_params_client
->
add_parameters
({
"foo"
,
"bar"
,
"foobar"
});
std
::
function
<
void
(
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
)
>
callback
=
[
node
](
const
rcl_interfaces
::
msg
::
ParameterEvent
::
SharedPtr
event
)
->
void
...
...
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