uncrustify ArduPlane/test.pde

This commit is contained in:
uncrustify 2012-08-21 19:19:51 -07:00 committed by Pat Hickey
parent fb727f65ac
commit e73834d6eb

View File

@ -44,9 +44,9 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
// Tests below here are for hardware sensors only present
// when real sensors are attached or they are emulated
#if HIL_MODE == HIL_MODE_DISABLED
#if CONFIG_ADC == ENABLED
#if CONFIG_ADC == ENABLED
{"adc", test_adc},
#endif
#endif
{"gps", test_gps},
{"rawgps", test_rawgps},
{"imu", test_imu},
@ -101,7 +101,7 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
delay(1000);
while(1){
while(1) {
delay(20);
// Filters radio input - adjust filters in the radio.pde file
@ -118,7 +118,7 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
(int)g.rc_7.radio_in,
(int)g.rc_8.radio_in);
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -131,20 +131,20 @@ test_passthru(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
delay(1000);
while(1){
while(1) {
delay(20);
// New radio frame? (we could use also if((millis()- timer) > 20)
if (APM_RC.GetState() == 1){
if (APM_RC.GetState() == 1) {
Serial.print("CH:");
for(int16_t i = 0; i < 8; i++){
for(int16_t i = 0; i < 8; i++) {
Serial.print(APM_RC.InputCh(i)); // Print channel values
Serial.print(",");
APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos
}
Serial.println();
}
if (Serial.available() > 0){
if (Serial.available() > 0) {
return (0);
}
}
@ -161,7 +161,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
// ---------------------------
trim_radio();
while(1){
while(1) {
delay(20);
read_radio();
@ -184,7 +184,7 @@ test_radio(uint8_t argc, const Menu::arg *argv)
(int)g.rc_7.control_in,
(int)g.rc_8.control_in);
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -195,7 +195,7 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
{
byte fail_test;
print_hit_enter();
for(int16_t i = 0; i < 50; i++){
for(int16_t i = 0; i < 50; i++) {
delay(20);
read_radio();
}
@ -207,36 +207,36 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
oldSwitchPosition = readSwitch();
Serial.printf_P(PSTR("Unplug battery, throttle in neutral, turn off radio.\n"));
while(g.channel_throttle.control_in > 0){
while(g.channel_throttle.control_in > 0) {
delay(20);
read_radio();
}
while(1){
while(1) {
delay(20);
read_radio();
if(g.channel_throttle.control_in > 0){
if(g.channel_throttle.control_in > 0) {
Serial.printf_P(PSTR("THROTTLE CHANGED %d \n"), (int)g.channel_throttle.control_in);
fail_test++;
}
if(oldSwitchPosition != readSwitch()){
if(oldSwitchPosition != readSwitch()) {
Serial.printf_P(PSTR("CONTROL MODE CHANGED: "));
Serial.println(flight_mode_strings[readSwitch()]);
fail_test++;
}
if(g.throttle_fs_enabled && g.channel_throttle.get_failsafe()){
if(g.throttle_fs_enabled && g.channel_throttle.get_failsafe()) {
Serial.printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), (int)g.channel_throttle.radio_in);
Serial.println(flight_mode_strings[readSwitch()]);
fail_test++;
}
if(fail_test > 0){
if(fail_test > 0) {
return (0);
}
if(Serial.available() > 0){
if(Serial.available() > 0) {
Serial.printf_P(PSTR("LOS caused no change in APM.\n"));
return (0);
}
@ -246,15 +246,15 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
static int8_t
test_battery(uint8_t argc, const Menu::arg *argv)
{
if (g.battery_monitoring == 3 || g.battery_monitoring == 4) {
if (g.battery_monitoring == 3 || g.battery_monitoring == 4) {
print_hit_enter();
delta_ms_medium_loop = 100;
while(1){
while(1) {
delay(100);
read_radio();
read_battery();
if (g.battery_monitoring == 3){
if (g.battery_monitoring == 3) {
Serial.printf_P(PSTR("V: %4.4f\n"),
battery_voltage1,
current_amps1,
@ -270,14 +270,14 @@ if (g.battery_monitoring == 3 || g.battery_monitoring == 4) {
// ------------------------------
set_servos();
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
} else {
} else {
Serial.printf_P(PSTR("Not enabled\n"));
return (0);
}
}
}
@ -287,18 +287,18 @@ test_relay(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
delay(1000);
while(1){
while(1) {
Serial.printf_P(PSTR("Relay on\n"));
relay.on();
delay(3000);
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
Serial.printf_P(PSTR("Relay off\n"));
relay.off();
delay(3000);
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -310,7 +310,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
delay(1000);
// save the alitude above home option
if (g.RTL_altitude_cm < 0){
if (g.RTL_altitude_cm < 0) {
Serial.printf_P(PSTR("Hold current altitude\n"));
}else{
Serial.printf_P(PSTR("Hold altitude of %dm\n"), (int)g.RTL_altitude_cm/100);
@ -320,7 +320,7 @@ test_wp(uint8_t argc, const Menu::arg *argv)
Serial.printf_P(PSTR("Hit radius: %d\n"), (int)g.waypoint_radius);
Serial.printf_P(PSTR("Loiter radius: %d\n\n"), (int)g.loiter_radius);
for(byte i = 0; i <= g.command_total; i++){
for(byte i = 0; i <= g.command_total; i++) {
struct Location temp = get_cmd_with_index(i);
test_wp_print(&temp, i);
}
@ -348,12 +348,12 @@ test_xbee(uint8_t argc, const Menu::arg *argv)
delay(1000);
Serial.printf_P(PSTR("Begin XBee X-CTU Range and RSSI Test:\n"));
while(1){
while(1) {
if (Serial3.available())
Serial3.write(Serial3.read());
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -370,21 +370,21 @@ test_modeswitch(uint8_t argc, const Menu::arg *argv)
Serial.println(FLIGHT_MODE_CHANNEL, DEC);
while(1){
while(1) {
delay(20);
byte switchPosition = readSwitch();
if (oldSwitchPosition != switchPosition){
if (oldSwitchPosition != switchPosition) {
Serial.printf_P(PSTR("Position %d\n"), (int)switchPosition);
oldSwitchPosition = switchPosition;
}
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
}
/*
test the dataflash is working
* test the dataflash is working
*/
static int8_t
test_logging(uint8_t argc, const Menu::arg *argv)
@ -412,7 +412,7 @@ test_logging(uint8_t argc, const Menu::arg *argv)
#if HIL_MODE == HIL_MODE_DISABLED || HIL_MODE == HIL_MODE_SENSORS
#if CONFIG_ADC == ENABLED
#if CONFIG_ADC == ENABLED
static int8_t
test_adc(uint8_t argc, const Menu::arg *argv)
{
@ -422,16 +422,16 @@ test_adc(uint8_t argc, const Menu::arg *argv)
Serial.printf_P(PSTR("ADC\n"));
delay(1000);
while(1){
for (int16_t i=0;i<9;i++) Serial.printf_P(PSTR("%.1f\t"),adc.Ch(i));
while(1) {
for (int16_t i=0; i<9; i++) Serial.printf_P(PSTR("%.1f\t"),adc.Ch(i));
Serial.println();
delay(100);
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
}
#endif // CONFIG_ADC
#endif // CONFIG_ADC
static int8_t
test_gps(uint8_t argc, const Menu::arg *argv)
@ -439,7 +439,7 @@ test_gps(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
delay(1000);
while(1){
while(1) {
delay(333);
// Blink GPS LED if we don't have a fix
@ -448,7 +448,7 @@ test_gps(uint8_t argc, const Menu::arg *argv)
g_gps->update();
if (g_gps->new_data){
if (g_gps->new_data) {
Serial.printf_P(PSTR("Lat: %ld, Lon %ld, Alt: %ldm, #sats: %d\n"),
(long)g_gps->latitude,
(long)g_gps->longitude,
@ -457,7 +457,7 @@ test_gps(uint8_t argc, const Menu::arg *argv)
}else{
Serial.printf_P(PSTR("."));
}
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -473,7 +473,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
delay(1000);
while(1){
while(1) {
delay(20);
if (millis() - fast_loopTimer_ms > 19) {
delta_ms_fast_loop = millis() - fast_loopTimer_ms;
@ -486,7 +486,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
if(g.compass_enabled) {
medium_loopCounter++;
if(medium_loopCounter == 5){
if(medium_loopCounter == 5) {
compass.read();
medium_loopCounter = 0;
}
@ -503,7 +503,7 @@ test_imu(uint8_t argc, const Menu::arg *argv)
gyros.x, gyros.y, gyros.z,
accels.x, accels.y, accels.z);
}
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -550,7 +550,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
ahrs.update();
medium_loopCounter++;
if(medium_loopCounter == 5){
if(medium_loopCounter == 5) {
if (compass.read()) {
// Calculate heading
Matrix3f m = ahrs.get_dcm_matrix();
@ -615,12 +615,12 @@ test_airspeed(uint8_t argc, const Menu::arg *argv)
Serial.printf_P(PSTR("airspeed: "));
print_enabled(true);
while(1){
while(1) {
delay(20);
read_airspeed();
Serial.printf_P(PSTR("%.1f m/s\n"), airspeed.get_airspeed());
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -638,7 +638,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
wp_distance = 0;
init_barometer();
while(1){
while(1) {
delay(100);
current_loc.alt = read_barometer() + home.alt;
@ -650,7 +650,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
barometer.get_pressure(), 0.1*barometer.get_temperature());
}
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}
@ -662,18 +662,18 @@ test_rawgps(uint8_t argc, const Menu::arg *argv)
print_hit_enter();
delay(1000);
while(1){
if (Serial3.available()){
while(1) {
if (Serial3.available()) {
digitalWrite(B_LED_PIN, LED_ON); // Blink Yellow LED if we are sending data to GPS
Serial1.write(Serial3.read());
digitalWrite(B_LED_PIN, LED_OFF);
}
if (Serial1.available()){
if (Serial1.available()) {
digitalWrite(C_LED_PIN, LED_ON); // Blink Red LED if we are receiving data from GPS
Serial3.write(Serial1.read());
digitalWrite(C_LED_PIN, LED_OFF);
}
if(Serial.available() > 0){
if(Serial.available() > 0) {
return (0);
}
}