mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
found the issue with stability - something to do with APVar.
commenting out setup_show(NULL,NULL); in startup_ground() causes some values to misload??? Or maybe it's a delay thing. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1839 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6b405c5831
commit
5ef54d2de4
@ -38,6 +38,7 @@ void handle_process_must()
|
|||||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||||
do_RTL();
|
do_RTL();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -488,7 +489,6 @@ void do_target_yaw()
|
|||||||
if(yaw_tracking & TRACK_TARGET_WP){
|
if(yaw_tracking & TRACK_TARGET_WP){
|
||||||
target_WP = next_command;
|
target_WP = next_command;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void do_loiter_at_location()
|
void do_loiter_at_location()
|
||||||
|
@ -93,7 +93,7 @@ void init_ardupilot()
|
|||||||
|
|
||||||
if (!g.format_version.load() ||
|
if (!g.format_version.load() ||
|
||||||
g.format_version != Parameters::k_format_version) {
|
g.format_version != Parameters::k_format_version) {
|
||||||
Serial.printf_P(PSTR("\n\nForcing complete parameter reset..."));
|
//Serial.printf_P(PSTR("\n\nForcing complete parameter reset..."));
|
||||||
|
|
||||||
/*Serial.printf_P(PSTR("\n\nEEPROM format version %d not compatible with this firmware (requires %d)"
|
/*Serial.printf_P(PSTR("\n\nEEPROM format version %d not compatible with this firmware (requires %d)"
|
||||||
"\n\nForcing complete parameter reset..."),
|
"\n\nForcing complete parameter reset..."),
|
||||||
@ -225,7 +225,7 @@ void startup_ground(void)
|
|||||||
delay(GROUND_START_DELAY * 1000);
|
delay(GROUND_START_DELAY * 1000);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//setup_show(NULL,NULL);
|
setup_show(NULL,NULL);
|
||||||
|
|
||||||
// Output waypoints for confirmation
|
// Output waypoints for confirmation
|
||||||
// --------------------------------
|
// --------------------------------
|
||||||
@ -319,14 +319,8 @@ void set_mode(byte mode)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case SIMPLE:
|
case SIMPLE:
|
||||||
if(g.rc_3.control_in == 0){ // we are on the ground
|
//initial_simple_bearing = dcm.yaw_sensor;
|
||||||
if(initial_simple_bearing == -1){ // only set once
|
init_simple_bearing();
|
||||||
initial_simple_bearing = dcm.yaw_sensor;
|
|
||||||
}
|
|
||||||
}else if(initial_simple_bearing == -1){ // we are flying
|
|
||||||
// don't enter simple mode
|
|
||||||
control_mode = STABILIZE; // just stabilize
|
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case LOITER:
|
case LOITER:
|
||||||
@ -464,3 +458,14 @@ unsigned long freeRAM() {
|
|||||||
return stackptr - heapptr;
|
return stackptr - heapptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
init_simple_bearing()
|
||||||
|
{
|
||||||
|
if(simple_bearing_is_set == false){
|
||||||
|
if(g.rc_3.control_in == 0){
|
||||||
|
// we are on the ground
|
||||||
|
initial_simple_bearing = dcm.yaw_sensor;
|
||||||
|
simple_bearing_is_set = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user