Copter: bug fix to loiter delay

change delay to seconds to allow delays longer than 65seconds
This commit is contained in:
Randy Mackay 2013-03-27 21:54:12 +09:00
parent a65960a009
commit 553f40a99c
2 changed files with 5 additions and 5 deletions

View File

@ -588,7 +588,7 @@ static float circle_angle;
static float circle_angle_total;
// deg : how many times to circle as specified by mission command
static uint8_t circle_desired_rotations;
// How long we should stay in Loiter Mode for mission scripting
// How long we should stay in Loiter Mode for mission scripting (time in seconds)
static uint16_t loiter_time_max;
// How long have we been loitering - The start time in millis
static uint32_t loiter_time;

View File

@ -290,7 +290,7 @@ static void do_nav_wp()
// this will be used to remember the time in millis after we reach or pass the WP.
loiter_time = 0;
// this is the delay, stored in seconds and expanded to millis
loiter_time_max = command_nav_queue.p1 * 1000;
loiter_time_max = command_nav_queue.p1;
}
// reset control of yaw to default
@ -407,7 +407,7 @@ static void do_loiter_time()
wp_nav.set_destination(pv_location_to_vector(command_nav_queue));
}
loiter_time_max = command_nav_queue.p1 * 1000; // units are (seconds)
loiter_time_max = command_nav_queue.p1; // units are (seconds)
}
/********************************************************************************/
@ -453,14 +453,14 @@ static bool verify_nav_wp()
}
// delay checking once we've reached the location
if( !(wp_verify_byte & NAV_DELAY) && (wp_verify_byte & (NAV_LOCATION | NAV_ALTITUDE)) ) {
if( !(wp_verify_byte & NAV_DELAY) && (wp_verify_byte & NAV_LOCATION) && (wp_verify_byte & NAV_ALTITUDE) ) {
// start timer if necessary
if(loiter_time == 0) {
loiter_time = millis();
}
// check if timer has run out
if ((millis() - loiter_time) >= loiter_time_max) {
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
wp_verify_byte |= NAV_DELAY;
}
}