Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
I
iri_ros_tools
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Service Desk
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
labrobotica
ros
iri_core
iri_ros_tools
Commits
812545ba
Commit
812545ba
authored
4 years ago
by
Sergi Hernandez
Browse files
Options
Downloads
Patches
Plain Diff
Solved a bug in the handling of the dynamic reconfigure parameters.
parent
1fb72ab7
No related branches found
No related tags found
1 merge request
!1
Added the dynamic_reconfigure function to handle generic parameters to the...
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
CMakeLists.txt
+1
-1
1 addition, 1 deletion
CMakeLists.txt
include/iri_ros_tools/module_action.h
+8
-6
8 additions, 6 deletions
include/iri_ros_tools/module_action.h
package.xml
+1
-0
1 addition, 0 deletions
package.xml
src/iri_ros_tools/dyn_params.py
+3
-3
3 additions, 3 deletions
src/iri_ros_tools/dyn_params.py
with
13 additions
and
10 deletions
CMakeLists.txt
+
1
−
1
View file @
812545ba
...
...
@@ -77,7 +77,7 @@ catkin_python_setup()
catkin_package
(
INCLUDE_DIRS include
LIBRARIES
${
PROJECT_NAME
}
CATKIN_DEPENDS roscpp
CATKIN_DEPENDS roscpp
rospy
)
###########
...
...
This diff is collapsed.
Click to expand it.
include/iri_ros_tools/module_action.h
+
8
−
6
View file @
812545ba
...
...
@@ -602,12 +602,11 @@ void CModuleAction<action_ros,dyn_reconf_config>::dynamic_reconfigure(dyn_reconf
boost
::
any
value
;
params
=
dyn_reconf_config
::
__getParamDescriptions__
();
for
(
typename
std
::
vector
<
typename
dyn_reconf_config
::
AbstractParamDescriptionConstPtr
>::
iterator
param
=
params
.
begin
();
param
!=
params
.
end
();
param
++
)
{
(
*
param
)
->
getValue
(
config
,
value
);
if
((
*
param
)
->
name
==
(
name
+
"_num_retries"
))
{
(
*
param
)
->
getValue
(
config
,
value
);
if
(
value
.
type
()
==
typeid
(
int
))
this
->
set_max_num_retries
(
boost
::
any_cast
<
int
&>
(
value
));
}
...
...
@@ -621,15 +620,13 @@ void CModuleAction<action_ros,dyn_reconf_config>::dynamic_reconfigure(dyn_reconf
enable_timeout
=
false
;
}
}
if
((
*
param
)
->
name
==
(
name
+
"_timeout_s"
))
else
if
((
*
param
)
->
name
==
(
name
+
"_timeout_s"
))
{
(
*
param
)
->
getValue
(
config
,
value
);
if
(
value
.
type
()
==
typeid
(
double
))
timeout
=
boost
::
any_cast
<
double
&>
(
value
);
}
if
((
*
param
)
->
name
==
(
name
+
"_feedback_watchdog_time_s"
))
else
if
((
*
param
)
->
name
==
(
name
+
"_feedback_watchdog_time_s"
))
{
(
*
param
)
->
getValue
(
config
,
value
);
if
(
value
.
type
()
==
typeid
(
double
))
watchdog
=
boost
::
any_cast
<
double
&>
(
value
);
}
...
...
@@ -660,6 +657,8 @@ void CModuleAction<action_ros,dyn_reconf_config>::dynamic_reconfigure(dyn_reconf
this
->
disable_timeout
();
if
(
enable_watchdog
)
this
->
enable_watchdog
(
watchdog
);
else
this
->
disable_watchdog
();
}
...
...
@@ -740,7 +739,10 @@ bool CModuleAction<action_ros,dyn_reconf_config>::is_watchdog_active(void)
}
}
else
{
this
->
action_access
.
exit
();
return
false
;
}
}
template
<
class
action_ros
,
class
dyn_reconf_config
>
...
...
This diff is collapsed.
Click to expand it.
package.xml
+
1
−
0
View file @
812545ba
...
...
@@ -14,6 +14,7 @@
<buildtool_depend>
catkin
</buildtool_depend>
<depend>
roscpp
</depend>
<depend>
rospy
</depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
...
...
This diff is collapsed.
Click to expand it.
src/iri_ros_tools/dyn_params.py
+
3
−
3
View file @
812545ba
...
...
@@ -14,9 +14,9 @@ def add_module_action_params(gen,name):
new_group
.
add
(
name
+
"
_num_retries
"
,
int_t
,
0
,
"
Number of times an action will be called before reporting an error
"
,
1
,
1
,
10
)
new_group
.
add
(
name
+
"
_enable_timeout
"
,
bool_t
,
0
,
"
Enable or disable the timeout feature
"
,
True
)
new_group
.
add
(
name
+
"
_timeout_s
"
,
double_t
,
0
,
"
Maximum time in second to wait for the action to complete
"
,
10.0
,
1.0
,
600.0
)
new_group
.
add
(
name
+
"
_enable_
i
watchdog
"
,
bool_t
,
0
,
"
Enable or disable the watchdog feature
"
,
True
)
new_group
.
add
(
name
+
"
_feedback_watchdog_time_s
"
,
double_t
,
0
,
"
Maximum time in second between two consecutive feedback topics
"
,
2.0
,
1.0
,
100.0
)
new_group
.
add
(
name
+
"
_timeout_s
"
,
double_t
,
0
,
"
Maximum time in second to wait for the action to complete
"
,
10.0
,
0.1
,
600.0
)
new_group
.
add
(
name
+
"
_enable_watchdog
"
,
bool_t
,
0
,
"
Enable or disable the watchdog feature
"
,
True
)
new_group
.
add
(
name
+
"
_feedback_watchdog_time_s
"
,
double_t
,
0
,
"
Maximum time in second between two consecutive feedback topics
"
,
2.0
,
0.1
,
100.0
)
new_group
.
add
(
name
+
"
_enabled
"
,
bool_t
,
0
,
"
Enable or disable the actual action request
"
,
True
)
return
new_group
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
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