Browse Source

Copter: bug fix for take-off in loiter

mission-4.1.18
Randy Mackay 12 years ago
parent
commit
05248738e2
  1. 4
      ArduCopter/ArduCopter.pde
  2. 3
      ArduCopter/navigation.pde

4
ArduCopter/ArduCopter.pde

@ -1752,8 +1752,8 @@ void update_roll_pitch_mode(void)
// if landed simply keep the copter level // if landed simply keep the copter level
if (ap.land_complete) { if (ap.land_complete) {
nav_roll = 0; nav_roll = ahrs.roll_sensor;
nav_pitch = 0; nav_pitch = ahrs.pitch_sensor;
}else{ }else{
// update loiter target from user controls // update loiter target from user controls
wp_nav.move_loiter_target(control_roll, control_pitch,0.01f); wp_nav.move_loiter_target(control_roll, control_pitch,0.01f);

3
ArduCopter/navigation.pde

@ -162,9 +162,10 @@ static void update_nav_mode()
// reset target if we are still on the ground // reset target if we are still on the ground
if (ap.land_complete) { if (ap.land_complete) {
wp_nav.init_loiter_target(inertial_nav.get_position(),inertial_nav.get_velocity()); wp_nav.init_loiter_target(inertial_nav.get_position(),inertial_nav.get_velocity());
} }else{
// call loiter controller // call loiter controller
wp_nav.update_loiter(); wp_nav.update_loiter();
}
break; break;
case NAV_WP: case NAV_WP:

Loading…
Cancel
Save