Merge branch 'multiwii-master'

Conflicts:
	src/board.h
	src/buzzer.c
	src/config.c
	src/drivers/serial_common.h
	src/drivers/system_common.c
	src/drv_gpio.h
	src/drv_pwm.c
	src/drv_timer.c
	src/drv_uart.c
	src/flight_imu.c
	src/mw.c
	src/rx_sbus.c
	src/sensors.c
	src/serial_cli.c
This commit is contained in:
Dominic Clifton 2014-05-11 18:17:40 +01:00
commit b3ee895f97
6 changed files with 3510 additions and 3499 deletions

File diff suppressed because it is too large Load Diff

View File

@ -92,7 +92,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
}
void resetGpsProfile(gpsProfile_t *gpsProfile)
{
{
gpsProfile->gps_wp_radius = 200;
gpsProfile->gps_lpf = 20;
gpsProfile->nav_slew_rate = 30;
@ -103,7 +103,7 @@ void resetGpsProfile(gpsProfile_t *gpsProfile)
}
void resetBarometerConfig(barometerConfig_t *barometerConfig)
{
{
barometerConfig->baro_sample_count = 21;
barometerConfig->baro_noise_lpf = 0.6f;
barometerConfig->baro_cf_vel = 0.985f;

View File

@ -456,7 +456,7 @@ int getEstimatedAltitude(void)
// set vario
vario = applyDeadband(vel_tmp, 5);
BaroPID = calculateBaroPid(vel_tmp, accZ_tmp, accZ_old);
accZ_old = accZ_tmp;

View File

@ -205,7 +205,7 @@ void annexCode(void)
// TODO MCU temp
}
}
static void mwArm(void)
{
if (isGyroCalibrationComplete() && f.ACC_CALIBRATED) {

View File

@ -94,23 +94,24 @@ static void sbusDataReceive(uint16_t c)
bool sbusFrameComplete(void)
{
if (sbusFrameDone) {
if (!((sbus.in[22] >> 3) & 0x0001)) { // failsave flag
sbusChannelData[0] = sbus.msg.chan0;
sbusChannelData[1] = sbus.msg.chan1;
sbusChannelData[2] = sbus.msg.chan2;
sbusChannelData[3] = sbus.msg.chan3;
sbusChannelData[4] = sbus.msg.chan4;
sbusChannelData[5] = sbus.msg.chan5;
sbusChannelData[6] = sbus.msg.chan6;
sbusChannelData[7] = sbus.msg.chan7;
// need more channels? No problem. Add them.
sbusFrameDone = false;
return true;
}
sbusFrameDone = false;
if (!sbusFrameDone) {
return false;
}
return false;
sbusFrameDone = false;
if ((sbus.in[22] >> 3) & 0x0001) {
// internal failsafe enabled and rx failsafe flag set
return false;
}
sbusChannelData[0] = sbus.msg.chan0;
sbusChannelData[1] = sbus.msg.chan1;
sbusChannelData[2] = sbus.msg.chan2;
sbusChannelData[3] = sbus.msg.chan3;
sbusChannelData[4] = sbus.msg.chan4;
sbusChannelData[5] = sbus.msg.chan5;
sbusChannelData[6] = sbus.msg.chan6;
sbusChannelData[7] = sbus.msg.chan7;
// need more channels? No problem. Add them.
return true;
}
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)

View File

@ -303,7 +303,6 @@ static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
static void cliPrintVar(const clivalue_t *var, uint32_t full);
static void cliPrint(const char *str);
static void cliWrite(uint8_t ch);
static void cliPrompt(void)
{
cliPrint("\r\n# ");