Gyro on Rev3 and Rev3a Bluejay are 0 aligned
This commit is contained in:
parent
552e32a287
commit
49f9eec1e9
|
@ -530,11 +530,7 @@ static void resetConf(void)
|
|||
masterConfig.rxConfig.rcSmoothing = RC_SMOOTHING_OFF;
|
||||
masterConfig.rxConfig.rcSmoothInterval = 9;
|
||||
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
|
||||
#ifdef STM32F4
|
||||
masterConfig.rxConfig.max_aux_channel = 99;
|
||||
#else
|
||||
masterConfig.rxConfig.max_aux_channel = 6;
|
||||
#endif
|
||||
masterConfig.rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
|
||||
masterConfig.rxConfig.airModeActivateThreshold = 1350;
|
||||
|
||||
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
|
||||
|
|
|
@ -213,7 +213,8 @@ bool m25p16_init(ioTag_t csTag)
|
|||
} else {
|
||||
#ifdef M25P16_CS_PIN
|
||||
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
|
||||
#else
return false;
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0);
|
||||
|
|
|
@ -0,0 +1,87 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/max7456.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
#include "hardware_revision.h"
|
||||
|
||||
// alternative defaults settings for BlueJayF4 targets
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) {
|
||||
masterConfig.sensorAlignmentConfig.gyro_align = CW180_DEG;
|
||||
masterConfig.sensorAlignmentConfig.acc_align = CW180_DEG;
|
||||
}
|
||||
}
|
|
@ -17,6 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
#define TARGET_BOARD_IDENTIFIER "BJF4"
|
||||
#define TARGET_CONFIG
|
||||
|
||||
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
|
||||
|
||||
|
@ -44,12 +45,12 @@
|
|||
#define ACC
|
||||
#define USE_ACC_MPU6500
|
||||
#define USE_ACC_SPI_MPU6500
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
#define ACC_MPU6500_ALIGN CW0_DEG
|
||||
|
||||
#define GYRO
|
||||
#define USE_GYRO_MPU6500
|
||||
#define USE_GYRO_SPI_MPU6500
|
||||
#define GYRO_MPU6500_ALIGN CW180_DEG
|
||||
#define GYRO_MPU6500_ALIGN CW0_DEG
|
||||
|
||||
//#define MAG
|
||||
//#define USE_MAG_AK8963
|
||||
|
|
|
@ -24,6 +24,7 @@
|
|||
/* STM32F4 specific settings that apply to all F4 targets */
|
||||
#ifdef STM32F4
|
||||
|
||||
#define MAX_AUX_CHANNELS 99
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 125
|
||||
#define SCHEDULER_DELAY_LIMIT 10
|
||||
#define USE_SLOW_SERIAL_CLI
|
||||
|
@ -31,6 +32,7 @@
|
|||
|
||||
#else /* when not an F4 */
|
||||
|
||||
#define MAX_AUX_CHANNELS 6
|
||||
#define TASK_GYROPID_DESIRED_PERIOD 1000
|
||||
#define SCHEDULER_DELAY_LIMIT 100
|
||||
|
||||
|
|
Loading…
Reference in New Issue