Skip to content
Snippets Groups Projects
Commit 8dd8d5c2 authored by Sergi Foix Salmerón's avatar Sergi Foix Salmerón
Browse files

updating nav_timeouts to 600

parent c97cc376
No related branches found
No related tags found
No related merge requests found
......@@ -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, 30)
move_base_action.add("mb_timeout_s",double_t, 0, "Maximum time allowed to complete the action", 1, 0.1, 600)
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, 30)
poi_action.add("poi_timeout_s",double_t, 0, "Maximum time allowed to complete the action", 1, 0.1, 600)
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, 30)
waypoint_action.add("wp_timeout_s",double_t, 0, "Maximum time allowed to complete the action", 1, 0.1, 600)
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)
......
......@@ -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 feedback received for a long time");
this->move_base_action.cancel();
this->state=NAV_MODULE_IDLE;
this->status=NAV_MODULE_FB_WATCHDOG;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment