mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Merge branch 'betaflight' into ready_to_merge
# Conflicts: # src/main/version.h
This commit is contained in:
commit
3e72bb5e3b
2 changed files with 15 additions and 1 deletions
|
@ -1272,7 +1272,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
serialize16(currentProfile->pidProfile.yaw_lpf_hz);
|
||||
break;
|
||||
case MSP_ADVANCED_TUNING:
|
||||
headSerialReply(3 * 3);
|
||||
headSerialReply(3 * 2);
|
||||
serialize16(currentProfile->pidProfile.rollPitchItermIgnoreRate);
|
||||
serialize16(currentProfile->pidProfile.yawItermIgnoreRate);
|
||||
serialize16(currentProfile->pidProfile.yaw_p_limit);
|
||||
|
@ -1281,6 +1281,12 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
headSerialReply(1);
|
||||
serialize8(currentControlRateProfile->rcYawRate8);
|
||||
break;
|
||||
case MSP_SENSOR_CONFIG:
|
||||
headSerialReply(3);
|
||||
serialize8(masterConfig.acc_hardware);
|
||||
serialize8(masterConfig.baro_hardware);
|
||||
serialize8(masterConfig.mag_hardware);
|
||||
break;
|
||||
|
||||
default:
|
||||
return false;
|
||||
|
@ -1848,6 +1854,11 @@ static bool processInCommand(void)
|
|||
case MSP_SET_TEMPORARY_COMMANDS:
|
||||
currentControlRateProfile->rcYawRate8 = read8();
|
||||
break;
|
||||
case MSP_SET_SENSOR_CONFIG:
|
||||
masterConfig.acc_hardware = read8();
|
||||
masterConfig.baro_hardware = read8();
|
||||
masterConfig.mag_hardware = read8();
|
||||
break;
|
||||
default:
|
||||
// we do not know how to handle the (valid) message, indicate error MSP $M!
|
||||
return false;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue