Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
I
iri_tiago_nav_module
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
Package Registry
Model registry
Operate
Environments
Terraform modules
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
platforms
TIAGo
iri_tiago_nav_module
Commits
8dd8d5c2
Commit
8dd8d5c2
authored
7 years ago
by
Sergi Foix Salmerón
Browse files
Options
Downloads
Patches
Plain Diff
updating nav_timeouts to 600
parent
c97cc376
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
cfg/NavModule.cfg
+3
-3
3 additions, 3 deletions
cfg/NavModule.cfg
src/nav_module.cpp
+1
-1
1 addition, 1 deletion
src/nav_module.cpp
with
4 additions
and
4 deletions
cfg/NavModule.cfg
+
3
−
3
View file @
8dd8d5c2
...
...
@@ -53,7 +53,7 @@ gen.add("rate_hz", double_t, 0,
move_base_action.add("mb_max_retries",int_t,
0, "Maximum number of retries for the action start", 1, 1, 10)
move_base_action.add("mb_feedback_watchdog_time_s",double_t,0,
"Maximum time between feedback messages", 1, 0.01, 600)
move_base_action.add("mb_enable_watchdog",bool_t,
0, "Enable action watchdog", True)
move_base_action.add("mb_timeout_s",double_t,
0, "Maximum time allowed to complete the action", 1, 0.1,
3
0)
move_base_action.add("mb_timeout_s",double_t,
0, "Maximum time allowed to complete the action", 1, 0.1,
60
0)
move_base_action.add("mb_enable_timeout",bool_t,
0, "Enable action timeout", True)
move_base_action.add("mb_frame_id",str_t,
0, "Reference frame of the position goals","/map")
move_base_action.add("mb_enabled",
bool_t, 0, "Enable action execution", True)
...
...
@@ -62,14 +62,14 @@ move_base_action.add("mb_cancel_prev", bool_t, 0,
poi_action.add("poi_max_retries",int_t,
0, "Maximum number of retries for the action start", 1, 1, 10)
poi_action.add("poi_feedback_watchdog_time_s",double_t,
0, "Maximum time between feedback messages", 1, 0.01, 600)
poi_action.add("poi_enable_watchdog",bool_t,
0, "Enable action watchdog", True)
poi_action.add("poi_timeout_s",double_t,
0, "Maximum time allowed to complete the action", 1, 0.1,
3
0)
poi_action.add("poi_timeout_s",double_t,
0, "Maximum time allowed to complete the action", 1, 0.1,
60
0)
poi_action.add("poi_enable_timeout",bool_t,
0, "Enable action timeout", True)
poi_action.add("poi_enabled",
bool_t, 0, "Enable action execution", True)
waypoint_action.add("wp_max_retries",int_t,
0, "Maximum number of retries for the action start", 1, 1, 10)
waypoint_action.add("wp_feedback_watchdog_time_s",double_t,
0, "Maximum time between feedback messages", 1, 0.01, 600)
waypoint_action.add("wp_enable_watchdog",bool_t,
0, "Enable action watchdog", True)
waypoint_action.add("wp_timeout_s",double_t,
0, "Maximum time allowed to complete the action", 1, 0.1,
3
0)
waypoint_action.add("wp_timeout_s",double_t,
0, "Maximum time allowed to complete the action", 1, 0.1,
60
0)
waypoint_action.add("wp_enable_timeout",bool_t,
0, "Enable action timeout", True)
waypoint_action.add("wp_enabled",
bool_t, 0, "Enable action execution", True)
...
...
This diff is collapsed.
Click to expand it.
src/nav_module.cpp
+
1
−
1
View file @
8dd8d5c2
...
...
@@ -160,7 +160,7 @@ void CNavModule::state_machine(void)
this
->
status
=
NAV_MODULE_TIMEOUT
;
this
->
move_base_action
.
stop_timeout
();
break
;
case
ACTION_FB_WATCHDOG
:
ROS_ERROR
(
"CNavModule : No feeback received for a long time"
);
case
ACTION_FB_WATCHDOG
:
ROS_ERROR
(
"CNavModule : No fee
d
back received for a long time"
);
this
->
move_base_action
.
cancel
();
this
->
state
=
NAV_MODULE_IDLE
;
this
->
status
=
NAV_MODULE_FB_WATCHDOG
;
...
...
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