1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Merge remote-tracking branch 'upstream/master' into blackbox-flash

This commit is contained in:
Nicholas Sherlock 2015-02-15 01:54:50 +13:00
commit acd4745a4e
65 changed files with 982 additions and 485 deletions

View file

@ -41,14 +41,9 @@
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "flight/flight.h"
#include "flight/mixer.h"
#include "flight/failsafe.h"
#include "flight/navigation.h"
#include "flight/altitudehold.h"
#include "rx/rx.h"
#include "rx/msp.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/gps.h"
@ -56,6 +51,7 @@
#include "io/serial.h"
#include "io/ledstrip.h"
#include "io/flashfs.h"
#include "telemetry/telemetry.h"
#include "sensors/boardalignment.h"
@ -67,6 +63,15 @@
#include "sensors/compass.h"
#include "sensors/gyro.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/failsafe.h"
#include "flight/navigation.h"
#include "flight/altitudehold.h"
#include "mw.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
@ -910,7 +915,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_PID:
headSerialReply(3 * PID_ITEM_COUNT);
if (currentProfile->pidController == 2) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) { // convert float stuff into uint8_t to keep backwards compatability with all 8-bit shit with new pid
for (i = 0; i < 3; i++) {
serialize8(constrain(lrintf(currentProfile->pidProfile.P_f[i] * 10.0f), 0, 250));
serialize8(constrain(lrintf(currentProfile->pidProfile.I_f[i] * 100.0f), 0, 250));
@ -941,7 +946,7 @@ static bool processOutCommand(uint8_t cmdMSP)
break;
case MSP_PID_CONTROLLER:
headSerialReply(1);
serialize8(currentProfile->pidController);
serialize8(currentProfile->pidProfile.pidController);
break;
case MSP_MODE_RANGES:
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
@ -1265,11 +1270,11 @@ static bool processInCommand(void)
currentProfile->accelerometerTrims.values.roll = read16();
break;
case MSP_SET_PID_CONTROLLER:
currentProfile->pidController = read8();
setPIDController(currentProfile->pidController);
currentProfile->pidProfile.pidController = read8();
setPIDController(currentProfile->pidProfile.pidController);
break;
case MSP_SET_PID:
if (currentProfile->pidController == 2) {
if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
for (i = 0; i < 3; i++) {
currentProfile->pidProfile.P_f[i] = (float)read8() / 10.0f;
currentProfile->pidProfile.I_f[i] = (float)read8() / 100.0f;