mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-25 17:25:18 +03:00
Merge branch 'master' into dzikuvx-drop-msp-frames
This commit is contained in:
commit
c7396b43d4
3 changed files with 0 additions and 352 deletions
|
@ -398,14 +398,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteData(dst, shortGitRevision, GIT_SHORT_REVISION_LENGTH);
|
||||
break;
|
||||
|
||||
// DEPRECATED - Use MSP_API_VERSION
|
||||
case MSP_IDENT:
|
||||
sbufWriteU8(dst, MW_VERSION);
|
||||
sbufWriteU8(dst, 3); //We no longer have mixerMode, just sent 3 (QuadX) as fallback
|
||||
sbufWriteU8(dst, MSP_PROTOCOL_VERSION);
|
||||
sbufWriteU32(dst, CAP_PLATFORM_32BIT | CAP_DYNBALANCE | CAP_FLAPS | CAP_NAVCAP | CAP_EXTAUX); // "capability"
|
||||
break;
|
||||
|
||||
#ifdef HIL
|
||||
case MSP_HIL_STATE:
|
||||
sbufWriteU16(dst, hilToSIM.pidCommand[ROLL]);
|
||||
|
@ -708,14 +700,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP_PID:
|
||||
for (int i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
sbufWriteU8(dst, constrain(pidBank()->pid[i].P, 0, 255));
|
||||
sbufWriteU8(dst, constrain(pidBank()->pid[i].I, 0, 255));
|
||||
sbufWriteU8(dst, constrain(pidBank()->pid[i].D, 0, 255));
|
||||
}
|
||||
break;
|
||||
|
||||
case MSP2_PID:
|
||||
for (int i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
sbufWriteU8(dst, constrain(pidBank()->pid[i].P, 0, 255));
|
||||
|
@ -731,10 +715,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP_PID_CONTROLLER:
|
||||
sbufWriteU8(dst, 2); // FIXME: Report as LuxFloat
|
||||
break;
|
||||
|
||||
case MSP_MODE_RANGES:
|
||||
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||
const modeActivationCondition_t *mac = modeActivationConditions(i);
|
||||
|
@ -1062,21 +1042,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteData(dst, rxConfig()->rcmap, MAX_MAPPABLE_RX_INPUTS);
|
||||
break;
|
||||
|
||||
case MSP_BF_CONFIG:
|
||||
sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback
|
||||
|
||||
sbufWriteU32(dst, featureMask());
|
||||
|
||||
sbufWriteU8(dst, rxConfig()->serialrx_provider);
|
||||
|
||||
sbufWriteU16(dst, boardAlignment()->rollDeciDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->pitchDeciDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->yawDeciDegrees);
|
||||
|
||||
sbufWriteU16(dst, batteryMetersConfig()->current.scale);
|
||||
sbufWriteU16(dst, batteryMetersConfig()->current.offset);
|
||||
break;
|
||||
|
||||
case MSP2_COMMON_SERIAL_CONFIG:
|
||||
for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
if (!serialIsPortAvailable(serialConfig()->portConfigs[i].identifier)) {
|
||||
|
@ -1174,12 +1139,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
#endif
|
||||
break;
|
||||
|
||||
case MSP_BF_BUILD_INFO:
|
||||
sbufWriteData(dst, buildDate, 11); // MMM DD YYYY as ascii, MMM = Jan/Feb... etc
|
||||
sbufWriteU32(dst, 0); // future exp
|
||||
sbufWriteU32(dst, 0); // future exp
|
||||
break;
|
||||
|
||||
case MSP_3D:
|
||||
sbufWriteU16(dst, reversibleMotorsConfig()->deadband_low);
|
||||
sbufWriteU16(dst, reversibleMotorsConfig()->deadband_high);
|
||||
|
@ -1679,23 +1638,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP_SET_PID_CONTROLLER:
|
||||
// FIXME: Do nothing
|
||||
break;
|
||||
|
||||
case MSP_SET_PID:
|
||||
if (dataSize >= PID_ITEM_COUNT * 3) {
|
||||
for (int i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
pidBankMutable()->pid[i].P = sbufReadU8(src);
|
||||
pidBankMutable()->pid[i].I = sbufReadU8(src);
|
||||
pidBankMutable()->pid[i].D = sbufReadU8(src);
|
||||
}
|
||||
schedulePidGainsUpdate();
|
||||
navigationUsePIDs();
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_SET_PID:
|
||||
if (dataSize >= PID_ITEM_COUNT * 4) {
|
||||
for (int i = 0; i < PID_ITEM_COUNT; i++) {
|
||||
|
@ -2683,26 +2625,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP_SET_BF_CONFIG:
|
||||
if (dataSize >= 16) {
|
||||
sbufReadU8(src); // mixerMode no longer supported, just swallow
|
||||
mixerUpdateStateFlags(); // Required for correct preset functionality
|
||||
|
||||
featureClearAll();
|
||||
featureSet(sbufReadU32(src)); // features bitmap
|
||||
|
||||
rxConfigMutable()->serialrx_provider = sbufReadU8(src); // serialrx_type
|
||||
|
||||
boardAlignmentMutable()->rollDeciDegrees = sbufReadU16(src); // board_align_roll
|
||||
boardAlignmentMutable()->pitchDeciDegrees = sbufReadU16(src); // board_align_pitch
|
||||
boardAlignmentMutable()->yawDeciDegrees = sbufReadU16(src); // board_align_yaw
|
||||
|
||||
batteryMetersConfigMutable()->current.scale = sbufReadU16(src);
|
||||
batteryMetersConfigMutable()->current.offset = sbufReadU16(src);
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
|
||||
case MSP2_COMMON_SET_SERIAL_CONFIG:
|
||||
{
|
||||
uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint32_t) + (sizeof(uint8_t) * 4);
|
||||
|
|
|
@ -26,7 +26,6 @@
|
|||
* if the API doesn't match EXACTLY.
|
||||
*
|
||||
* Consumers of the API (API clients) SHOULD first attempt to get a response from the MSP_API_VERSION command.
|
||||
* If no response is obtained then client MAY try the legacy MSP_IDENT command.
|
||||
*
|
||||
* API consumers should ALWAYS handle communication failures gracefully and attempt to continue
|
||||
* without the information if possible. Clients MAY log/display a suitable message.
|
||||
|
@ -164,9 +163,6 @@
|
|||
|
||||
#define MSP_SONAR_ALTITUDE 58 //out message get surface altitude [cm]
|
||||
|
||||
#define MSP_PID_CONTROLLER 59
|
||||
#define MSP_SET_PID_CONTROLLER 60
|
||||
|
||||
#define MSP_ARMING_CONFIG 61 //out message Returns auto_disarm_delay and disarm_kill_switch parameters
|
||||
#define MSP_SET_ARMING_CONFIG 62 //in message Sets auto_disarm_delay and disarm_kill_switch parameters
|
||||
|
||||
|
@ -176,17 +172,8 @@
|
|||
#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total)
|
||||
#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
|
||||
|
||||
// FIXME - Provided for backwards compatibility with configurator code until configurator is updated.
|
||||
// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead.
|
||||
#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
|
||||
#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save
|
||||
|
||||
#define MSP_REBOOT 68 //in message reboot settings
|
||||
|
||||
// DEPRECATED - Use MSP_BUILD_INFO instead
|
||||
#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion
|
||||
|
||||
|
||||
#define MSP_DATAFLASH_SUMMARY 70 //out message - get description of dataflash chip
|
||||
#define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip
|
||||
#define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip
|
||||
|
@ -197,10 +184,6 @@
|
|||
#define MSP_FAILSAFE_CONFIG 75 //out message Returns FC Fail-Safe settings
|
||||
#define MSP_SET_FAILSAFE_CONFIG 76 //in message Sets FC Fail-Safe settings
|
||||
|
||||
// DEPRECATED
|
||||
//#define MSP_RXFAIL_CONFIG 77 //out message Returns RXFAIL settings
|
||||
//#define MSP_SET_RXFAIL_CONFIG 78 //in message Sets RXFAIL settings
|
||||
|
||||
#define MSP_SDCARD_SUMMARY 79 //out message Get the state of the SD card
|
||||
|
||||
#define MSP_BLACKBOX_CONFIG 80 //out message Get blackbox settings
|
||||
|
@ -249,10 +232,6 @@
|
|||
// Multwii original MSP commands
|
||||
//
|
||||
|
||||
// DEPRECATED - See MSP_API_VERSION and MSP_MIXER
|
||||
#define MSP_IDENT 100 //out message mixerMode + multiwii version + protocol version + capability variable
|
||||
|
||||
|
||||
#define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number
|
||||
#define MSP_RAW_IMU 102 //out message 9 DOF
|
||||
#define MSP_SERVO 103 //out message servos
|
||||
|
@ -264,7 +243,6 @@
|
|||
#define MSP_ALTITUDE 109 //out message altitude, variometer
|
||||
#define MSP_ANALOG 110 //out message vbat, powermetersum, rssi if available on RX
|
||||
#define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
|
||||
#define MSP_PID 112 //out message P I D coeff (9 are used currently)
|
||||
#define MSP_ACTIVEBOXES 113 //out message Active box flags (full width, more than 32 bits)
|
||||
#define MSP_MISC 114 //out message powermeter trig
|
||||
#define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI
|
||||
|
@ -282,7 +260,6 @@
|
|||
|
||||
#define MSP_SET_RAW_RC 200 //in message 8 rc chan
|
||||
#define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed
|
||||
#define MSP_SET_PID 202 //in message P I D coeff (9 are used currently)
|
||||
#define MSP_SET_BOX 203 //in message BOX setup (number is dependant of your setup)
|
||||
#define MSP_SET_RC_TUNING 204 //in message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID, yaw expo
|
||||
#define MSP_ACC_CALIBRATION 205 //in message no param
|
||||
|
|
|
@ -229,257 +229,6 @@ TEST_F(SerialMspUnitTest, TestMspProcessReceivedCommand)
|
|||
checksum = FLIGHT_CONTROLLER_VERSION_LENGTH ^ MSP_FC_VERSION;
|
||||
checksum ^= FC_VERSION_MAJOR ^ FC_VERSION_MINOR ^ FC_VERSION_PATCH_LEVEL;
|
||||
EXPECT_EQ(checksum, serialBuffer.mspResponse.payload[3]);
|
||||
|
||||
// check the MSP_PID_CONTROLLER is written out correctly
|
||||
serialWritePos = 0;
|
||||
serialReadPos = 0;
|
||||
currentProfile = &profile;
|
||||
currentProfile->pidProfile.pidController = PID_CONTROLLER_MWREWRITE;
|
||||
currentPort->cmdMSP = MSP_PID_CONTROLLER;
|
||||
mspProcessReceivedCommand();
|
||||
EXPECT_EQ('$', serialBuffer.mspResponse.header.dollar);
|
||||
EXPECT_EQ('M', serialBuffer.mspResponse.header.m);
|
||||
EXPECT_EQ('>', serialBuffer.mspResponse.header.direction);
|
||||
EXPECT_EQ(1, serialBuffer.mspResponse.header.size);
|
||||
EXPECT_EQ(MSP_PID_CONTROLLER, serialBuffer.mspResponse.header.type);
|
||||
EXPECT_EQ(PID_CONTROLLER_MWREWRITE, serialBuffer.mspResponse.payload[0]);
|
||||
checksum = 1 ^ MSP_PID_CONTROLLER ^ PID_CONTROLLER_MWREWRITE;
|
||||
EXPECT_EQ(checksum, serialBuffer.mspResponse.payload[1]);
|
||||
}
|
||||
|
||||
TEST_F(SerialMspUnitTest, Test_PID_CONTROLLER)
|
||||
{
|
||||
// Use the MSP to write out the PID values
|
||||
currentProfile = &profile;
|
||||
currentProfile->pidProfile.pidController = PID_CONTROLLER_MWREWRITE;
|
||||
serialWritePos = 0;
|
||||
serialReadPos = 0;
|
||||
currentPort->cmdMSP = MSP_PID_CONTROLLER;
|
||||
mspProcessReceivedCommand();
|
||||
EXPECT_EQ(PID_CONTROLLER_MWREWRITE, serialBuffer.mspResponse.payload[0]);
|
||||
|
||||
// set the pidController to a different value so we can check if it gets read back properly
|
||||
currentProfile->pidProfile.pidController = PID_CONTROLLER_LUX_FLOAT;
|
||||
|
||||
// Now use the MSP to read back the picController and check if it is the same
|
||||
// spoof a change from the written MSP_PID_CONTROLLER to the readable MSP_SET_PID_CONTROLLER
|
||||
currentPort->cmdMSP = MSP_SET_PID_CONTROLLER;
|
||||
serialBuffer.mspResponse.header.direction = '<';
|
||||
serialBuffer.mspResponse.header.type = currentPort->cmdMSP;
|
||||
// force the checksum
|
||||
serialBuffer.mspResponse.payload[1] ^= MSP_PID_CONTROLLER;
|
||||
serialBuffer.mspResponse.payload[1] ^= MSP_SET_PID_CONTROLLER;
|
||||
// copy the command data into the current port inBuf so it can be processed
|
||||
memcpy(currentPort->inBuf, serialBuffer.buf, MSP_PORT_INBUF_SIZE);
|
||||
|
||||
// set the offset into the payload
|
||||
currentPort->indRX = offsetof(struct mspResonse_s, payload);
|
||||
mspProcessReceivedCommand();
|
||||
|
||||
// check the pidController value has been read correctly
|
||||
EXPECT_EQ(PID_CONTROLLER_MWREWRITE, currentProfile->pidProfile.pidController);
|
||||
}
|
||||
|
||||
TEST_F(SerialMspUnitTest, Test_PIDValuesInt)
|
||||
{
|
||||
// check the buffer is big enough for the data to read in
|
||||
EXPECT_LE(sizeof(mspHeader_t) + 3 * PID_ITEM_COUNT + 1, MSP_PORT_INBUF_SIZE); // +1 for checksum
|
||||
// set up some test data
|
||||
const int P8_ROLL = 40;
|
||||
const int I8_ROLL = 30;
|
||||
const int D8_ROLL = 23;
|
||||
const int P8_PITCH = 41;
|
||||
const int I8_PITCH = 31;
|
||||
const int D8_PITCH = 24;
|
||||
const int P8_YAW = 85;
|
||||
const int I8_YAW = 45;
|
||||
const int D8_YAW = 1;
|
||||
const int P8_PIDALT = 50;
|
||||
const int I8_PIDALT = 2;
|
||||
const int D8_PIDALT = 3;
|
||||
const int P8_PIDPOS = 15; // POSHOLD_P * 100;
|
||||
const int I8_PIDPOS = 4; // POSHOLD_I * 100;
|
||||
const int D8_PIDPOS = 5;
|
||||
const int P8_PIDPOSR = 34; // POSHOLD_RATE_P * 10;
|
||||
const int I8_PIDPOSR = 14; // POSHOLD_RATE_I * 100;
|
||||
const int D8_PIDPOSR = 53; // POSHOLD_RATE_D * 1000;
|
||||
const int P8_PIDNAVR = 25; // NAV_P * 10;
|
||||
const int I8_PIDNAVR = 33; // NAV_I * 100;
|
||||
const int D8_PIDNAVR = 83; // NAV_D * 1000;
|
||||
const int P8_PIDLEVEL = 90;
|
||||
const int I8_PIDLEVEL = 10;
|
||||
const int D8_PIDLEVEL = 100;
|
||||
const int P8_PIDMAG = 40;
|
||||
const int P8_PIDVEL = 120;
|
||||
const int I8_PIDVEL = 45;
|
||||
const int D8_PIDVEL = 7;
|
||||
|
||||
currentProfile = &profile;
|
||||
currentProfile->pidProfile.pidController = PID_CONTROLLER_MWREWRITE;
|
||||
currentProfile->pidProfile.P8[PIDROLL] = P8_ROLL;
|
||||
currentProfile->pidProfile.I8[PIDROLL] = I8_ROLL;
|
||||
currentProfile->pidProfile.D8[PIDROLL] = D8_ROLL;
|
||||
currentProfile->pidProfile.P8[PIDPITCH] = P8_PITCH;
|
||||
currentProfile->pidProfile.I8[PIDPITCH] = I8_PITCH;
|
||||
currentProfile->pidProfile.D8[PIDPITCH] = D8_PITCH;
|
||||
currentProfile->pidProfile.P8[PIDYAW] = P8_YAW;
|
||||
currentProfile->pidProfile.I8[PIDYAW] = I8_YAW;
|
||||
currentProfile->pidProfile.D8[PIDYAW] = D8_YAW;
|
||||
currentProfile->pidProfile.P8[PIDALT] = P8_PIDALT;
|
||||
currentProfile->pidProfile.I8[PIDALT] = I8_PIDALT;
|
||||
currentProfile->pidProfile.D8[PIDALT] = D8_PIDALT;
|
||||
currentProfile->pidProfile.P8[PIDPOS] = P8_PIDPOS;
|
||||
currentProfile->pidProfile.I8[PIDPOS] = I8_PIDPOS;
|
||||
currentProfile->pidProfile.D8[PIDPOS] = D8_PIDPOS;
|
||||
currentProfile->pidProfile.P8[PIDPOSR] = P8_PIDPOSR;
|
||||
currentProfile->pidProfile.I8[PIDPOSR] = I8_PIDPOSR;
|
||||
currentProfile->pidProfile.D8[PIDPOSR] = D8_PIDPOSR;
|
||||
currentProfile->pidProfile.P8[PIDNAVR] = P8_PIDNAVR;
|
||||
currentProfile->pidProfile.I8[PIDNAVR] = I8_PIDNAVR;
|
||||
currentProfile->pidProfile.D8[PIDNAVR] = D8_PIDNAVR;
|
||||
currentProfile->pidProfile.P8[PIDLEVEL] = P8_PIDLEVEL;
|
||||
currentProfile->pidProfile.I8[PIDLEVEL] = I8_PIDLEVEL;
|
||||
currentProfile->pidProfile.D8[PIDLEVEL] = D8_PIDLEVEL;
|
||||
currentProfile->pidProfile.P8[PIDMAG] = P8_PIDMAG;
|
||||
currentProfile->pidProfile.P8[PIDVEL] = P8_PIDVEL;
|
||||
currentProfile->pidProfile.I8[PIDVEL] = I8_PIDVEL;
|
||||
currentProfile->pidProfile.D8[PIDVEL] = D8_PIDVEL;
|
||||
|
||||
// use the MSP to write out the PID values
|
||||
serialWritePos = 0;
|
||||
serialReadPos = 0;
|
||||
currentPort->cmdMSP = MSP_PID;
|
||||
mspProcessReceivedCommand();
|
||||
EXPECT_EQ(3 * PID_ITEM_COUNT, serialBuffer.mspResponse.header.size);
|
||||
// check few values, just to make sure they have been written correctly
|
||||
EXPECT_EQ(P8_YAW, serialBuffer.mspResponse.payload[6]);
|
||||
EXPECT_EQ(I8_YAW, serialBuffer.mspResponse.payload[7]);
|
||||
EXPECT_EQ(D8_YAW, serialBuffer.mspResponse.payload[8]);
|
||||
|
||||
// reset test values to zero, so we can check if they get read properly
|
||||
memset(¤tProfile->pidProfile, 0, sizeof(currentProfile->pidProfile));
|
||||
|
||||
// now use the MSP to read back the PID values and check they are the same as written
|
||||
// spoof a change from the written MSP_PID to the readable MSP_SET_PID
|
||||
currentPort->cmdMSP = MSP_SET_PID;
|
||||
serialBuffer.mspResponse.header.direction = '<';
|
||||
serialBuffer.mspResponse.header.type = currentPort->cmdMSP;
|
||||
// force the checksum
|
||||
serialBuffer.mspResponse.payload[3 * PID_ITEM_COUNT] ^= MSP_PID;
|
||||
serialBuffer.mspResponse.payload[3 * PID_ITEM_COUNT] ^= MSP_SET_PID;
|
||||
// copy the command data into the current port inBuf so it can be processed
|
||||
memcpy(currentPort->inBuf, serialBuffer.buf, MSP_PORT_INBUF_SIZE);
|
||||
|
||||
// set the offset into the payload
|
||||
currentPort->indRX = offsetof(struct mspResonse_s, payload);
|
||||
mspProcessReceivedCommand();
|
||||
|
||||
// check the values are as expected
|
||||
EXPECT_EQ(P8_ROLL, currentProfile->pidProfile.P8[PIDROLL]);
|
||||
EXPECT_EQ(I8_ROLL, currentProfile->pidProfile.I8[PIDROLL]);
|
||||
EXPECT_EQ(D8_ROLL, currentProfile->pidProfile.D8[PIDROLL]);
|
||||
EXPECT_EQ(P8_PITCH, currentProfile->pidProfile.P8[PIDPITCH]);
|
||||
EXPECT_EQ(I8_PITCH, currentProfile->pidProfile.I8[PIDPITCH]);
|
||||
EXPECT_EQ(D8_PITCH, currentProfile->pidProfile.D8[PIDPITCH]);
|
||||
EXPECT_EQ(P8_YAW, currentProfile->pidProfile.P8[PIDYAW]);
|
||||
EXPECT_EQ(I8_YAW, currentProfile->pidProfile.I8[PIDYAW]);
|
||||
EXPECT_EQ(D8_YAW, currentProfile->pidProfile.D8[PIDYAW]);
|
||||
EXPECT_EQ(P8_PIDALT, currentProfile->pidProfile.P8[PIDALT]);
|
||||
EXPECT_EQ(I8_PIDALT, currentProfile->pidProfile.I8[PIDALT]);
|
||||
EXPECT_EQ(D8_PIDALT, currentProfile->pidProfile.D8[PIDALT]);
|
||||
EXPECT_EQ(P8_PIDPOS, currentProfile->pidProfile.P8[PIDPOS]);
|
||||
EXPECT_EQ(I8_PIDPOS, currentProfile->pidProfile.I8[PIDPOS]);
|
||||
EXPECT_EQ(D8_PIDPOS, currentProfile->pidProfile.D8[PIDPOS]);
|
||||
EXPECT_EQ(P8_PIDPOSR, currentProfile->pidProfile.P8[PIDPOSR]);
|
||||
EXPECT_EQ(I8_PIDPOSR, currentProfile->pidProfile.I8[PIDPOSR]);
|
||||
EXPECT_EQ(D8_PIDPOSR, currentProfile->pidProfile.D8[PIDPOSR]);
|
||||
EXPECT_EQ(P8_PIDNAVR, currentProfile->pidProfile.P8[PIDNAVR]);
|
||||
EXPECT_EQ(I8_PIDNAVR, currentProfile->pidProfile.I8[PIDNAVR]);
|
||||
EXPECT_EQ(D8_PIDNAVR, currentProfile->pidProfile.D8[PIDNAVR]);
|
||||
EXPECT_EQ(P8_PIDLEVEL, currentProfile->pidProfile.P8[PIDLEVEL]);
|
||||
EXPECT_EQ(I8_PIDLEVEL, currentProfile->pidProfile.I8[PIDLEVEL]);
|
||||
EXPECT_EQ(D8_PIDLEVEL, currentProfile->pidProfile.D8[PIDLEVEL]);
|
||||
EXPECT_EQ(P8_PIDMAG, currentProfile->pidProfile.P8[PIDMAG]);
|
||||
EXPECT_EQ(P8_PIDVEL, currentProfile->pidProfile.P8[PIDVEL]);
|
||||
EXPECT_EQ(I8_PIDVEL, currentProfile->pidProfile.I8[PIDVEL]);
|
||||
EXPECT_EQ(D8_PIDVEL, currentProfile->pidProfile.D8[PIDVEL]);
|
||||
}
|
||||
|
||||
TEST_F(SerialMspUnitTest, Test_PIDValuesFloat)
|
||||
{
|
||||
// check the buffer is big enough for the data to read in
|
||||
EXPECT_LE(sizeof(mspHeader_t) + 3 * PID_ITEM_COUNT + 1, MSP_PORT_INBUF_SIZE); // +1 for checksum
|
||||
|
||||
// set up some test data
|
||||
// use test values close to default, but make sure they are all different
|
||||
const float Pf_ROLL = 1.4f;
|
||||
const float If_ROLL = 0.4f;
|
||||
const float Df_ROLL = 0.03f;
|
||||
const float Pf_PITCH = 1.5f; // default 1.4
|
||||
const float If_PITCH = 0.5f; // default 0.4
|
||||
const float Df_PITCH = 0.02f; // default 0.03
|
||||
const float Pf_YAW = 3.5f;
|
||||
const float If_YAW = 0.6f; // default 0.4
|
||||
const float Df_YAW = 0.01;
|
||||
const float A_level = 5.0f;
|
||||
const float H_level = 3.0f;
|
||||
const uint8_t H_sensitivity = 75;
|
||||
currentProfile = &profile;
|
||||
currentProfile->pidProfile.pidController = PID_CONTROLLER_LUX_FLOAT;
|
||||
currentProfile->pidProfile.P_f[PIDROLL] = Pf_ROLL;
|
||||
currentProfile->pidProfile.I_f[PIDROLL] = If_ROLL;
|
||||
currentProfile->pidProfile.D_f[PIDROLL] = Df_ROLL;
|
||||
currentProfile->pidProfile.P_f[PIDPITCH] = Pf_PITCH;
|
||||
currentProfile->pidProfile.I_f[PIDPITCH] = If_PITCH;
|
||||
currentProfile->pidProfile.D_f[PIDPITCH] = Df_PITCH;
|
||||
currentProfile->pidProfile.P_f[PIDYAW] = Pf_YAW;
|
||||
currentProfile->pidProfile.I_f[PIDYAW] = If_YAW;
|
||||
currentProfile->pidProfile.D_f[PIDYAW] = Df_YAW;
|
||||
currentProfile->pidProfile.A_level = A_level;
|
||||
currentProfile->pidProfile.H_level = H_level;
|
||||
currentProfile->pidProfile.H_sensitivity = H_sensitivity;
|
||||
|
||||
// use the MSP to write out the PID values
|
||||
serialWritePos = 0;
|
||||
serialReadPos = 0;
|
||||
currentPort->cmdMSP = MSP_PID;
|
||||
mspProcessReceivedCommand();
|
||||
EXPECT_EQ(3 * PID_ITEM_COUNT, serialBuffer.mspResponse.header.size);
|
||||
|
||||
// reset test values to zero, so we can check if they get read properly
|
||||
memset(¤tProfile->pidProfile, 0, sizeof(currentProfile->pidProfile));
|
||||
|
||||
// now use the MSP to read back the PID values and check they are the same
|
||||
// spoof a change from the written MSP_PID to the readable MSP_SET_PID
|
||||
currentPort->cmdMSP = MSP_SET_PID;
|
||||
serialBuffer.mspResponse.header.direction = '<';
|
||||
serialBuffer.mspResponse.header.type = currentPort->cmdMSP;
|
||||
// force the checksum
|
||||
serialBuffer.mspResponse.payload[3 * PID_ITEM_COUNT] ^= MSP_PID;
|
||||
serialBuffer.mspResponse.payload[3 * PID_ITEM_COUNT] ^= MSP_SET_PID;
|
||||
// copy the command data into the current port inBuf so it can be processed
|
||||
memcpy(currentPort->inBuf, serialBuffer.buf, MSP_PORT_INBUF_SIZE);
|
||||
|
||||
// need to reset the controller for values to be read back correctly
|
||||
currentProfile->pidProfile.pidController = PID_CONTROLLER_LUX_FLOAT;
|
||||
|
||||
// set the offset into the payload
|
||||
currentPort->indRX = offsetof(struct mspResonse_s, payload);
|
||||
mspProcessReceivedCommand();
|
||||
|
||||
// check the values are as expected
|
||||
EXPECT_FLOAT_EQ(Pf_ROLL, currentProfile->pidProfile.P_f[PIDROLL]);
|
||||
EXPECT_FLOAT_EQ(If_ROLL, currentProfile->pidProfile.I_f[PIDROLL]);
|
||||
EXPECT_FLOAT_EQ(Df_ROLL, currentProfile->pidProfile.D_f[PIDROLL]);
|
||||
EXPECT_FLOAT_EQ(Pf_PITCH, currentProfile->pidProfile.P_f[PIDPITCH]);
|
||||
EXPECT_FLOAT_EQ(If_PITCH, currentProfile->pidProfile.I_f[PIDPITCH]);
|
||||
EXPECT_FLOAT_EQ(Df_PITCH, currentProfile->pidProfile.D_f[PIDPITCH]);
|
||||
EXPECT_FLOAT_EQ(Pf_YAW, currentProfile->pidProfile.P_f[PIDYAW]);
|
||||
EXPECT_FLOAT_EQ(If_YAW, currentProfile->pidProfile.I_f[PIDYAW]);
|
||||
EXPECT_FLOAT_EQ(Df_YAW, currentProfile->pidProfile.D_f[PIDYAW]);
|
||||
EXPECT_FLOAT_EQ(A_level, currentProfile->pidProfile.A_level);
|
||||
EXPECT_FLOAT_EQ(H_level, currentProfile->pidProfile.H_level);
|
||||
EXPECT_EQ(H_sensitivity, currentProfile->pidProfile.H_sensitivity);
|
||||
}
|
||||
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue