Skip to content

Commit

Permalink
Copter: reboot after accel cal
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall committed May 26, 2015
1 parent d0f6552 commit c67c1c8
Showing 1 changed file with 2 additions and 0 deletions.
2 changes: 2 additions & 0 deletions ArduCopter/GCS_Mavlink.pde
Original file line number Diff line number Diff line change
Expand Up @@ -1211,6 +1211,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if(ins.calibrate_accel(&interact, trim_roll, trim_pitch)) {
// reset ahrs's trim to suggested values from calibration routine
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
hal.scheduler->delay(1000);
hal.scheduler->reboot(false);
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
Expand Down

0 comments on commit c67c1c8

Please sign in to comment.