Browse Source

Copter: updates for new compass API

mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
0d027b7a23
  1. 1
      ArduCopter/APM_Config.h
  2. 8
      ArduCopter/config.h
  3. 1
      ArduCopter/sensors.pde
  4. 1
      ArduCopter/test.pde

1
ArduCopter/APM_Config.h

@ -7,7 +7,6 @@ @@ -7,7 +7,6 @@
// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
// valid! You should switch to using a HAL_BOARD flag in your local config.mk.
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
//#define HIL_MODE HIL_MODE_SENSORS
//#define DMP_ENABLED ENABLED
//#define SECONDARY_DMP_ENABLED ENABLED // allows running DMP in parallel with DCM for testing purposes

8
ArduCopter/config.h

@ -59,7 +59,6 @@ @@ -59,7 +59,6 @@
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_APM2_SHIELD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
# ifdef APM2_BETA_HARDWARE
@ -72,7 +71,6 @@ @@ -72,7 +71,6 @@
# define CONFIG_IMU_TYPE CONFIG_IMU_SITL
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4
@ -80,7 +78,6 @@ @@ -80,7 +78,6 @@
# define CONFIG_BARO AP_BARO_PX4
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION ROTATION_NONE
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#elif CONFIG_HAL_BOARD == HAL_BOARD_SMACCM
@ -90,7 +87,6 @@ @@ -90,7 +87,6 @@
# define CONFIG_ADC DISABLED
# define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_BACK
# define CONFIG_SONAR_SOURCE SONAR_SOURCE_ANALOG_PIN
# define MAGNETOMETER ENABLED
#endif
@ -413,10 +409,6 @@ @@ -413,10 +409,6 @@
#ifndef MAGNETOMETER
# define MAGNETOMETER ENABLED
#endif
#ifndef MAG_ORIENTATION
# define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#endif
//////////////////////////////////////////////////////////////////////////////
// OPTICAL_FLOW

1
ArduCopter/sensors.pde

@ -65,7 +65,6 @@ static int16_t read_sonar(void) @@ -65,7 +65,6 @@ static int16_t read_sonar(void)
static void init_compass()
{
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
if (!compass.init() || !compass.read()) {
// make sure we don't pass a broken compass to DCM
cliSerial->println_P(PSTR("COMPASS INIT ERROR"));

1
ArduCopter/test.pde

@ -440,7 +440,6 @@ test_mag(uint8_t argc, const Menu::arg *argv) @@ -440,7 +440,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;

Loading…
Cancel
Save