Browse Source

Plane: updates for new compass API

mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
a019e3740e
  1. 3
      ArduPlane/APM_Config.h.reference
  2. 7
      ArduPlane/config.h
  3. 1
      ArduPlane/setup.pde
  4. 1
      ArduPlane/system.pde
  5. 3
      ArduPlane/test.pde

3
ArduPlane/APM_Config.h.reference

@ -91,15 +91,12 @@ @@ -91,15 +91,12 @@
//////////////////////////////////////////////////////////////////////////////
// MAGNETOMETER OPTIONAL
// MAG_ORIENTATION OPTIONAL
//
// 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.
//
//#define MAGNETOMETER DISABLED
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
//
//////////////////////////////////////////////////////////////////////////////

7
ArduPlane/config.h

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

1
ArduPlane/setup.pde

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

1
ArduPlane/system.pde

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

3
ArduPlane/test.pde

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

Loading…
Cancel
Save