mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
APM: save another few bytes
This commit is contained in:
parent
bd2eae8a18
commit
a00e00519f
@ -298,9 +298,6 @@ AP_Relay relay;
|
|||||||
static bool usb_connected;
|
static bool usb_connected;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static const char *comma = ",";
|
|
||||||
|
|
||||||
|
|
||||||
/* Radio values
|
/* Radio values
|
||||||
* Channel assignments
|
* Channel assignments
|
||||||
* 1 Ailerons
|
* 1 Ailerons
|
||||||
|
@ -405,9 +405,9 @@ static void Log_Read_Control_Tuning()
|
|||||||
if(y < 8) logvar = logvar/100.f;
|
if(y < 8) logvar = logvar/100.f;
|
||||||
if(y == 9) logvar = logvar/10000.f;
|
if(y == 9) logvar = logvar/10000.f;
|
||||||
Serial.print(logvar);
|
Serial.print(logvar);
|
||||||
Serial.print(comma);
|
print_comma();
|
||||||
}
|
}
|
||||||
Serial.println(" ");
|
Serial.println();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read a nav tuning packet
|
// Read a nav tuning packet
|
||||||
@ -436,7 +436,7 @@ static void Log_Read_Performance()
|
|||||||
Serial.printf_P(PSTR("PM:"));
|
Serial.printf_P(PSTR("PM:"));
|
||||||
pm_time = DataFlash.ReadLong();
|
pm_time = DataFlash.ReadLong();
|
||||||
Serial.print(pm_time);
|
Serial.print(pm_time);
|
||||||
Serial.print(comma);
|
print_comma();
|
||||||
for (int16_t y = 1; y <= 12; y++) {
|
for (int16_t y = 1; y <= 12; y++) {
|
||||||
if(y < 3 || y > 7) {
|
if(y < 3 || y > 7) {
|
||||||
logvar = DataFlash.ReadInt();
|
logvar = DataFlash.ReadInt();
|
||||||
@ -444,9 +444,9 @@ static void Log_Read_Performance()
|
|||||||
logvar = DataFlash.ReadByte();
|
logvar = DataFlash.ReadByte();
|
||||||
}
|
}
|
||||||
Serial.print(logvar);
|
Serial.print(logvar);
|
||||||
Serial.print(comma);
|
print_comma();
|
||||||
}
|
}
|
||||||
Serial.println(" ");
|
Serial.println();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read a command processing packet
|
// Read a command processing packet
|
||||||
@ -459,14 +459,14 @@ static void Log_Read_Cmd()
|
|||||||
for(int16_t i = 1; i < 4; i++) {
|
for(int16_t i = 1; i < 4; i++) {
|
||||||
logvarb = DataFlash.ReadByte();
|
logvarb = DataFlash.ReadByte();
|
||||||
Serial.print(logvarb, DEC);
|
Serial.print(logvarb, DEC);
|
||||||
Serial.print(comma);
|
print_comma();
|
||||||
}
|
}
|
||||||
for(int16_t i = 1; i < 4; i++) {
|
for(int16_t i = 1; i < 4; i++) {
|
||||||
logvarl = DataFlash.ReadLong();
|
logvarl = DataFlash.ReadLong();
|
||||||
Serial.print(logvarl, DEC);
|
Serial.print(logvarl, DEC);
|
||||||
Serial.print(comma);
|
print_comma();
|
||||||
}
|
}
|
||||||
Serial.println(" ");
|
Serial.println();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void Log_Read_Startup()
|
static void Log_Read_Startup()
|
||||||
@ -533,9 +533,9 @@ static void Log_Read_Raw()
|
|||||||
for (int16_t y = 0; y < 6; y++) {
|
for (int16_t y = 0; y < 6; y++) {
|
||||||
logvar = (float)DataFlash.ReadLong() / t7;
|
logvar = (float)DataFlash.ReadLong() / t7;
|
||||||
Serial.print(logvar);
|
Serial.print(logvar);
|
||||||
Serial.print(comma);
|
print_comma();
|
||||||
}
|
}
|
||||||
Serial.println(" ");
|
Serial.println();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read the DataFlash log memory : Packet Parser
|
// Read the DataFlash log memory : Packet Parser
|
||||||
|
@ -534,7 +534,7 @@ print_blanks(int16_t num)
|
|||||||
{
|
{
|
||||||
while(num > 0) {
|
while(num > 0) {
|
||||||
num--;
|
num--;
|
||||||
Serial.println("");
|
Serial.println();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -544,7 +544,7 @@ print_divider(void)
|
|||||||
for (int16_t i = 0; i < 40; i++) {
|
for (int16_t i = 0; i < 40; i++) {
|
||||||
Serial.printf_P(PSTR("-"));
|
Serial.printf_P(PSTR("-"));
|
||||||
}
|
}
|
||||||
Serial.println("");
|
Serial.println();
|
||||||
}
|
}
|
||||||
|
|
||||||
static int8_t
|
static int8_t
|
||||||
|
@ -602,3 +602,8 @@ print_flight_mode(uint8_t mode)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void print_comma(void)
|
||||||
|
{
|
||||||
|
Serial.print_P(PSTR(","));
|
||||||
|
}
|
||||||
|
@ -136,10 +136,10 @@ test_passthru(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
// New radio frame? (we could use also if((millis()- timer) > 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:");
|
Serial.print_P(PSTR("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.InputCh(i)); // Print channel values
|
||||||
Serial.print(",");
|
print_comma();
|
||||||
APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos
|
APM_RC.OutputCh(i, APM_RC.InputCh(i)); // Copy input to Servos
|
||||||
}
|
}
|
||||||
Serial.println();
|
Serial.println();
|
||||||
|
Loading…
Reference in New Issue
Block a user