mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
APM: fixed some compiler warnings
This commit is contained in:
parent
d07d42403e
commit
cde7d8c5e7
@ -43,7 +43,7 @@ static void reload_commands_airstart()
|
|||||||
static struct Location get_cmd_with_index(int16_t i)
|
static struct Location get_cmd_with_index(int16_t i)
|
||||||
{
|
{
|
||||||
struct Location temp;
|
struct Location temp;
|
||||||
int32_t mem;
|
uint16_t mem;
|
||||||
|
|
||||||
// Find out proper location in memory by using the start_byte position + the index
|
// Find out proper location in memory by using the start_byte position + the index
|
||||||
// --------------------------------------------------------------------------------
|
// --------------------------------------------------------------------------------
|
||||||
@ -53,22 +53,22 @@ static struct Location get_cmd_with_index(int16_t i)
|
|||||||
}else{
|
}else{
|
||||||
// read WP position
|
// read WP position
|
||||||
mem = (WP_START_BYTE) + (i * WP_SIZE);
|
mem = (WP_START_BYTE) + (i * WP_SIZE);
|
||||||
temp.id = eeprom_read_byte((uint8_t*)mem);
|
temp.id = eeprom_read_byte((uint8_t*)(uintptr_t)mem);
|
||||||
|
|
||||||
mem++;
|
mem++;
|
||||||
temp.options = eeprom_read_byte((uint8_t*)mem);
|
temp.options = eeprom_read_byte((uint8_t*)(uintptr_t)mem);
|
||||||
|
|
||||||
mem++;
|
mem++;
|
||||||
temp.p1 = eeprom_read_byte((uint8_t*)mem);
|
temp.p1 = eeprom_read_byte((uint8_t*)(uintptr_t)mem);
|
||||||
|
|
||||||
mem++;
|
mem++;
|
||||||
temp.alt = (long)eeprom_read_dword((uint32_t*)mem);
|
temp.alt = (long)eeprom_read_dword((uint32_t*)(uintptr_t)mem);
|
||||||
|
|
||||||
mem += 4;
|
mem += 4;
|
||||||
temp.lat = (long)eeprom_read_dword((uint32_t*)mem);
|
temp.lat = (long)eeprom_read_dword((uint32_t*)(uintptr_t)mem);
|
||||||
|
|
||||||
mem += 4;
|
mem += 4;
|
||||||
temp.lng = (long)eeprom_read_dword((uint32_t*)mem);
|
temp.lng = (long)eeprom_read_dword((uint32_t*)(uintptr_t)mem);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative
|
// Add on home altitude if we are a nav command (or other command with altitude) and stored alt is relative
|
||||||
|
@ -120,15 +120,6 @@ static void process_next_command()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**************************************************/
|
|
||||||
// These functions implement the commands.
|
|
||||||
/**************************************************/
|
|
||||||
static void process_nav_cmd()
|
|
||||||
{
|
|
||||||
//gcs_send_text_P(SEVERITY_LOW,PSTR("New nav command loaded"));
|
|
||||||
handle_process_nav_cmd();
|
|
||||||
}
|
|
||||||
|
|
||||||
static void process_non_nav_command()
|
static void process_non_nav_command()
|
||||||
{
|
{
|
||||||
//gcs_send_text_P(SEVERITY_LOW,PSTR("new non-nav command loaded"));
|
//gcs_send_text_P(SEVERITY_LOW,PSTR("new non-nav command loaded"));
|
||||||
|
Loading…
Reference in New Issue
Block a user