AP_Declination: fixed build under SITL

This commit is contained in:
Andrew Tridgell 2012-03-30 13:23:18 +11:00
parent 9c414e9573
commit 01c4cde14f
3 changed files with 23 additions and 3 deletions

View File

@ -194,7 +194,7 @@ AP_Declination::get_lookup_value(uint8_t x, uint8_t y)
for(i = start_index; i < (start_index + declination_keys[1][x]) && current_virtual_index <= y; i++){ for(i = start_index; i < (start_index + declination_keys[1][x]) && current_virtual_index <= y; i++){
// Pull out the row_value struct // Pull out the row_value struct
memcpy_P((void*) &stval, (void *) &declination_values[i], sizeof(struct row_value)); memcpy_P((void*) &stval, (const prog_char *)&declination_values[i], sizeof(struct row_value));
// Pull the first offset and determine sign // Pull the first offset and determine sign
offset = stval.abs_offset; offset = stval.abs_offset;
@ -208,4 +208,4 @@ AP_Declination::get_lookup_value(uint8_t x, uint8_t y)
} }
} }
return val; return val;
} }

View File

@ -5,6 +5,23 @@
#include <AP_Common.h> #include <AP_Common.h>
#include <AP_Math.h> #include <AP_Math.h>
#include <AP_Declination.h> #include <AP_Declination.h>
#include <Filter.h>
#ifdef DESKTOP_BUILD
// all of this is needed to build with SITL
#include <DataFlash.h>
#include <APM_RC.h>
#include <GCS_MAVLink.h>
#include <Arduino_Mega_ISR_Registry.h>
#include <AP_PeriodicProcess.h>
#include <AP_ADC.h>
#include <AP_Baro.h>
#include <AP_Compass.h>
#include <AP_GPS.h>
Arduino_Mega_ISR_Registry isr_registry;
AP_Baro_BMP085_HIL barometer;
AP_Compass_HIL compass;
#endif
FastSerialPort(Serial, 0); FastSerialPort(Serial, 0);
@ -108,4 +125,4 @@ float get_declination(float lat, float lon)
decmin = (lon - lonmin) / 5 * (decSE - decSW) + decSW; decmin = (lon - lonmin) / 5 * (decSE - decSW) + decSW;
decmax = (lon - lonmin) / 5 * (decNE - decNW) + decNW; decmax = (lon - lonmin) / 5 * (decNE - decNW) + decNW;
return (lat - latmin) / 5 * (decmax - decmin) + decmin; return (lat - latmin) / 5 * (decmax - decmin) + decmin;
} }

View File

@ -1 +1,4 @@
include ../../../AP_Common/Arduino.mk include ../../../AP_Common/Arduino.mk
sitl:
make -f ../../../../libraries/Desktop/Desktop.mk