mirror of https://github.com/ArduPilot/ardupilot
APM: fixed some build warnings
This commit is contained in:
parent
3907cf81f8
commit
df2ef6ff47
|
@ -2104,14 +2104,6 @@ static void gcs_update(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void gcs_send_text(gcs_severity severity, const char *str)
|
|
||||||
{
|
|
||||||
gcs0.send_text(severity, str);
|
|
||||||
if (gcs3.initialised) {
|
|
||||||
gcs3.send_text(severity, str);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
|
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
|
||||||
{
|
{
|
||||||
gcs0.send_text(severity, str);
|
gcs0.send_text(severity, str);
|
||||||
|
|
|
@ -1,5 +1,7 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
|
||||||
|
#if 0 // currently unused
|
||||||
|
|
||||||
struct DataPoint {
|
struct DataPoint {
|
||||||
unsigned long x;
|
unsigned long x;
|
||||||
long y;
|
long y;
|
||||||
|
@ -17,8 +19,7 @@ long yi;
|
||||||
long xiyi;
|
long xiyi;
|
||||||
unsigned long xi2;
|
unsigned long xi2;
|
||||||
|
|
||||||
#if 0 // currently unused
|
void add_altitude_data(unsigned long xl, long y)
|
||||||
static void add_altitude_data(unsigned long xl, long y)
|
|
||||||
{
|
{
|
||||||
//Reset the regression if our X variable overflowed
|
//Reset the regression if our X variable overflowed
|
||||||
if (xl < xoffset)
|
if (xl < xoffset)
|
||||||
|
|
|
@ -1,19 +1,7 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
|
/*
|
||||||
/* Functions in this file:
|
logic for dealing with the current command in the mission and home location
|
||||||
void init_commands()
|
*/
|
||||||
void update_auto()
|
|
||||||
void reload_commands_airstart()
|
|
||||||
struct Location get_cmd_with_index(int i)
|
|
||||||
void set_cmd_with_index(struct Location temp, int i)
|
|
||||||
void increment_cmd_index()
|
|
||||||
void decrement_cmd_index()
|
|
||||||
long read_alt_to_hold()
|
|
||||||
void set_next_WP(struct Location *wp)
|
|
||||||
void set_guided_WP(void)
|
|
||||||
void init_home()
|
|
||||||
************************************************************
|
|
||||||
*/
|
|
||||||
|
|
||||||
static void init_commands()
|
static void init_commands()
|
||||||
{
|
{
|
||||||
|
@ -125,13 +113,6 @@ static void set_cmd_with_index(struct Location temp, int i)
|
||||||
eeprom_write_dword((uint32_t *) mem, temp.lng);
|
eeprom_write_dword((uint32_t *) mem, temp.lng);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void increment_cmd_index()
|
|
||||||
{
|
|
||||||
if (g.command_index <= g.command_total) {
|
|
||||||
g.command_index.set_and_save(g.command_index + 1);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void decrement_cmd_index()
|
static void decrement_cmd_index()
|
||||||
{
|
{
|
||||||
if (g.command_index > 0) {
|
if (g.command_index > 0) {
|
||||||
|
|
|
@ -79,7 +79,7 @@ static void failsafe_short_off_event()
|
||||||
}
|
}
|
||||||
|
|
||||||
#if BATTERY_EVENT == ENABLED
|
#if BATTERY_EVENT == ENABLED
|
||||||
static void low_battery_event(void)
|
void low_battery_event(void)
|
||||||
{
|
{
|
||||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Low Battery!"));
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("Low Battery!"));
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
|
|
Loading…
Reference in New Issue