mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Add MSP command to allow changing pid controller.
This commit is contained in:
parent
104a263533
commit
203c744763
1 changed files with 11 additions and 1 deletions
|
@ -125,7 +125,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
||||||
#define MSP_PROTOCOL_VERSION 0
|
#define MSP_PROTOCOL_VERSION 0
|
||||||
|
|
||||||
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
#define API_VERSION_MAJOR 1 // increment when major changes are made
|
||||||
#define API_VERSION_MINOR 4 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
#define API_VERSION_MINOR 5 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
|
||||||
|
|
||||||
#define API_VERSION_LENGTH 2
|
#define API_VERSION_LENGTH 2
|
||||||
|
|
||||||
|
@ -209,6 +209,8 @@ const char *boardIdentifier = TARGET_BOARD_IDENTIFIER;
|
||||||
|
|
||||||
#define MSP_SONAR_ALTITUDE 58 //out message get sonar altitude [cm]
|
#define MSP_SONAR_ALTITUDE 58 //out message get sonar altitude [cm]
|
||||||
|
|
||||||
|
#define MSP_PID_CONTROLLER 59
|
||||||
|
#define MSP_SET_PID_CONTROLLER 60
|
||||||
//
|
//
|
||||||
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
// Baseflight MSP commands (if enabled they exist in Cleanflight)
|
||||||
//
|
//
|
||||||
|
@ -892,6 +894,10 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
headSerialReply(sizeof(pidnames) - 1);
|
headSerialReply(sizeof(pidnames) - 1);
|
||||||
serializeNames(pidnames);
|
serializeNames(pidnames);
|
||||||
break;
|
break;
|
||||||
|
case MSP_PID_CONTROLLER:
|
||||||
|
headSerialReply(1);
|
||||||
|
serialize8(currentProfile->pidController);
|
||||||
|
break;
|
||||||
case MSP_MODE_RANGES:
|
case MSP_MODE_RANGES:
|
||||||
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
|
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
|
||||||
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||||
|
@ -1198,6 +1204,10 @@ static bool processInCommand(void)
|
||||||
currentProfile->accelerometerTrims.values.pitch = read16();
|
currentProfile->accelerometerTrims.values.pitch = read16();
|
||||||
currentProfile->accelerometerTrims.values.roll = read16();
|
currentProfile->accelerometerTrims.values.roll = read16();
|
||||||
break;
|
break;
|
||||||
|
case MSP_SET_PID_CONTROLLER:
|
||||||
|
currentProfile->pidController = read8();
|
||||||
|
setPIDController(currentProfile->pidController);
|
||||||
|
break;
|
||||||
case MSP_SET_PID:
|
case MSP_SET_PID:
|
||||||
if (currentProfile->pidController == 2) {
|
if (currentProfile->pidController == 2) {
|
||||||
for (i = 0; i < 3; i++) {
|
for (i = 0; i < 3; i++) {
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue