Plane: updates for new compass API

This commit is contained in:
Andrew Tridgell 2013-05-02 12:28:26 +10:00
parent 0d027b7a23
commit a019e3740e
5 changed files with 0 additions and 15 deletions

View File

@ -91,15 +91,12 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// MAGNETOMETER OPTIONAL // MAGNETOMETER OPTIONAL
// MAG_ORIENTATION OPTIONAL
// //
// Set MAGNETOMETER to ENABLED if you have a magnetometer attached. // Set MAGNETOMETER to ENABLED if you have a magnetometer attached.
// Set MAG_ORIENTATION to reflect the orientation you have the magnetometer mounted with respect to ArduPilotMega
// //
// The default assumes that a magnetometer is not connected. // The default assumes that a magnetometer is not connected.
// //
//#define MAGNETOMETER DISABLED //#define MAGNETOMETER DISABLED
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
// //
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////

View File

@ -119,7 +119,6 @@
# define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN # define CONFIG_PITOT_SOURCE PITOT_SOURCE_ANALOG_PIN
# define CONFIG_PITOT_SOURCE_ANALOG_PIN 0 # define CONFIG_PITOT_SOURCE_ANALOG_PIN 0
# define CONFIG_PITOT_SCALING 4.0 # define CONFIG_PITOT_SCALING 4.0
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# ifdef APM2_BETA_HARDWARE # ifdef APM2_BETA_HARDWARE
# define CONFIG_BARO AP_BARO_BMP085 # define CONFIG_BARO AP_BARO_BMP085
@ -157,7 +156,6 @@
# define CONFIG_PITOT_SOURCE_ANALOG_PIN 11 # define CONFIG_PITOT_SOURCE_ANALOG_PIN 11
# define CONFIG_PITOT_SCALING (4.0*5.0/3.3) # define CONFIG_PITOT_SCALING (4.0*5.0/3.3)
# define MAGNETOMETER ENABLED # define MAGNETOMETER ENABLED
# define MAG_ORIENTATION ROTATION_NONE
# define CONFIG_BARO AP_BARO_PX4 # define CONFIG_BARO AP_BARO_PX4
# define CONFIG_COMPASS AP_COMPASS_PX4 # define CONFIG_COMPASS AP_COMPASS_PX4
# define SERIAL0_BAUD 115200 # define SERIAL0_BAUD 115200
@ -272,11 +270,6 @@
# define MAGNETOMETER DISABLED # define MAGNETOMETER DISABLED
#endif #endif
#ifndef MAG_ORIENTATION
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION // RADIO CONFIGURATION

View File

@ -412,7 +412,6 @@ static int8_t
setup_compass(uint8_t argc, const Menu::arg *argv) setup_compass(uint8_t argc, const Menu::arg *argv)
{ {
if (!strcmp_P(argv[1].str, PSTR("on"))) { if (!strcmp_P(argv[1].str, PSTR("on"))) {
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
if (!compass.init()) { if (!compass.init()) {
cliSerial->println_P(PSTR("Compass initialisation failed!")); cliSerial->println_P(PSTR("Compass initialisation failed!"));
g.compass_enabled = false; g.compass_enabled = false;

View File

@ -160,7 +160,6 @@ static void init_ardupilot()
barometer.init(); barometer.init();
if (g.compass_enabled==true) { if (g.compass_enabled==true) {
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
if (!compass.init() || !compass.read()) { if (!compass.init() || !compass.read()) {
cliSerial->println_P(PSTR("Compass initialisation failed!")); cliSerial->println_P(PSTR("Compass initialisation failed!"));
g.compass_enabled = false; g.compass_enabled = false;

View File

@ -526,7 +526,6 @@ test_mag(uint8_t argc, const Menu::arg *argv)
return (0); return (0);
} }
compass.set_orientation(MAG_ORIENTATION);
if (!compass.init()) { if (!compass.init()) {
cliSerial->println_P(PSTR("Compass initialisation failed!")); cliSerial->println_P(PSTR("Compass initialisation failed!"));
return 0; return 0;
@ -545,8 +544,6 @@ test_mag(uint8_t argc, const Menu::arg *argv)
int16_t counter = 0; int16_t counter = 0;
float heading = 0; float heading = 0;
//cliSerial->printf_P(PSTR("MAG_ORIENTATION: %d\n"), MAG_ORIENTATION);
print_hit_enter(); print_hit_enter();
while(1) { while(1) {