Skip to content

Commit

Permalink
Copter: bug fix for take-off in loiter
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Jul 28, 2013
1 parent c3daf78 commit 0524873
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 4 deletions.
4 changes: 2 additions & 2 deletions ArduCopter/ArduCopter.pde
Original file line number Diff line number Diff line change
Expand Up @@ -1752,8 +1752,8 @@ void update_roll_pitch_mode(void)

// if landed simply keep the copter level
if (ap.land_complete) {
nav_roll = 0;
nav_pitch = 0;
nav_roll = ahrs.roll_sensor;
nav_pitch = ahrs.pitch_sensor;
}else{
// update loiter target from user controls
wp_nav.move_loiter_target(control_roll, control_pitch,0.01f);
Expand Down
5 changes: 3 additions & 2 deletions ArduCopter/navigation.pde
Original file line number Diff line number Diff line change
Expand Up @@ -162,9 +162,10 @@ static void update_nav_mode()
// reset target if we are still on the ground
if (ap.land_complete) {
wp_nav.init_loiter_target(inertial_nav.get_position(),inertial_nav.get_velocity());
}else{
// call loiter controller
wp_nav.update_loiter();
}
// call loiter controller
wp_nav.update_loiter();
break;

case NAV_WP:
Expand Down

0 comments on commit 0524873

Please sign in to comment.