uncrustify libraries/AP_Navigation/examples/Navigation/Navigation.pde

This commit is contained in:
uncrustify 2012-08-16 23:20:45 -07:00 committed by Pat Hickey
parent 4062cca4e0
commit 841774f512

View File

@ -1,8 +1,8 @@
/* /*
*
This test assumes you are at the LOWl demo Airport * This test assumes you are at the LOWl demo Airport
*
*/ */
#include "Waypoints.h" #include "Waypoints.h"
#include "Navigation.h" #include "Navigation.h"
@ -57,8 +57,8 @@ void loop()
servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], 0, 100); servo_out[CH_THROTTLE] = constrain(servo_out[CH_THROTTLE], 0, 100);
output_Xplane(); output_Xplane();
if(gps.new_data /* && gps.fix */ ){ if(gps.new_data /* && gps.fix */ ) {
if(did_init_home == 0){ if(did_init_home == 0) {
did_init_home = 1; did_init_home = 1;
Waypoints::WP wp = {0, 0, gps.altitude, gps.lattitude, gps.longitude}; Waypoints::WP wp = {0, 0, gps.altitude, gps.lattitude, gps.longitude};
nav.set_home(wp); nav.set_home(wp);
@ -143,7 +143,7 @@ void print_buffer()
{ {
byte ck_a = 0; byte ck_a = 0;
byte ck_b = 0; byte ck_b = 0;
for (byte i = 0;i < buf_len; i++){ for (byte i = 0; i < buf_len; i++) {
Serial.print (out_buffer[i]); Serial.print (out_buffer[i]);
} }
Serial.print('\r'); Serial.print('\r');