Merge pull request #2716 from betaflight/remove-msp-cruft
Remove msp/bst cruft
This commit is contained in:
commit
b55b46a2b5
|
@ -94,7 +94,10 @@ enum {
|
|||
|
||||
#define AIRMODE_THOTTLE_THRESHOLD 1350 // Make configurable in the future. ~35% throttle should be fine
|
||||
|
||||
#if defined(GPS) || defined(MAG)
|
||||
int16_t magHold;
|
||||
#endif
|
||||
|
||||
int16_t headFreeModeHold;
|
||||
|
||||
uint8_t motorControlEnable = false;
|
||||
|
@ -261,6 +264,7 @@ static void updateInflightCalibrationState(void)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(GPS) || defined(MAG)
|
||||
void updateMagHold(void)
|
||||
{
|
||||
if (ABS(rcCommand[YAW]) < 15 && FLIGHT_MODE(MAG_MODE)) {
|
||||
|
@ -275,6 +279,8 @@ void updateMagHold(void)
|
|||
} else
|
||||
magHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
void processRx(timeUs_t currentTimeUs)
|
||||
{
|
||||
|
@ -411,6 +417,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
|
||||
#if defined(ACC) || defined(MAG)
|
||||
if (sensors(SENSOR_ACC) || sensors(SENSOR_MAG)) {
|
||||
#if defined(GPS) || defined(MAG)
|
||||
if (IS_RC_MODE_ACTIVE(BOXMAG)) {
|
||||
if (!FLIGHT_MODE(MAG_MODE)) {
|
||||
ENABLE_FLIGHT_MODE(MAG_MODE);
|
||||
|
@ -419,6 +426,7 @@ void processRx(timeUs_t currentTimeUs)
|
|||
} else {
|
||||
DISABLE_FLIGHT_MODE(MAG_MODE);
|
||||
}
|
||||
#endif
|
||||
if (IS_RC_MODE_ACTIVE(BOXHEADFREE)) {
|
||||
if (!FLIGHT_MODE(HEADFREE_MODE)) {
|
||||
ENABLE_FLIGHT_MODE(HEADFREE_MODE);
|
||||
|
|
|
@ -20,7 +20,10 @@
|
|||
#include "common/time.h"
|
||||
#include "config/parameter_group.h"
|
||||
|
||||
#if defined(GPS) || defined(MAG)
|
||||
extern int16_t magHold;
|
||||
#endif
|
||||
|
||||
extern bool isRXDataNew;
|
||||
extern int16_t headFreeModeHold;
|
||||
|
||||
|
|
|
@ -65,10 +65,6 @@
|
|||
#include "drivers/exti.h"
|
||||
#include "drivers/vtx_soft_spi_rtc6705.h"
|
||||
|
||||
#ifdef USE_BST
|
||||
#include "bus_bst.h"
|
||||
#endif
|
||||
|
||||
#include "fc/config.h"
|
||||
#include "fc/fc_init.h"
|
||||
#include "fc/fc_msp.h"
|
||||
|
@ -316,10 +312,6 @@ void init(void)
|
|||
initInverters();
|
||||
#endif
|
||||
|
||||
#ifdef USE_BST
|
||||
bstInit(BST_DEVICE);
|
||||
#endif
|
||||
|
||||
#ifdef TARGET_BUS_INIT
|
||||
targetBusInit();
|
||||
#else
|
||||
|
|
|
@ -596,14 +596,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteData(dst, shortGitRevision, GIT_SHORT_REVISION_LENGTH);
|
||||
break;
|
||||
|
||||
// DEPRECATED - Use MSP_API_VERSION
|
||||
case MSP_IDENT:
|
||||
sbufWriteU8(dst, MW_VERSION);
|
||||
sbufWriteU8(dst, mixerConfig()->mixerMode);
|
||||
sbufWriteU8(dst, MSP_PROTOCOL_VERSION);
|
||||
sbufWriteU32(dst, CAP_DYNBALANCE); // "capability"
|
||||
break;
|
||||
|
||||
case MSP_STATUS_EX:
|
||||
sbufWriteU16(dst, getTaskDeltaTime(TASK_GYROPID));
|
||||
#ifdef USE_I2C
|
||||
|
@ -739,10 +731,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, armingConfig()->disarm_kill_switch);
|
||||
break;
|
||||
|
||||
case MSP_LOOP_TIME:
|
||||
sbufWriteU16(dst, (uint16_t)gyro.targetLooptime);
|
||||
break;
|
||||
|
||||
case MSP_RC_TUNING:
|
||||
sbufWriteU8(dst, currentControlRateProfile->rcRate8);
|
||||
sbufWriteU8(dst, currentControlRateProfile->rcExpo8);
|
||||
|
@ -812,44 +800,24 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP_MISC:
|
||||
sbufWriteU16(dst, rxConfig()->midrc);
|
||||
|
||||
case MSP_MOTOR_CONFIG:
|
||||
sbufWriteU16(dst, motorConfig()->minthrottle);
|
||||
sbufWriteU16(dst, motorConfig()->maxthrottle);
|
||||
sbufWriteU16(dst, motorConfig()->mincommand);
|
||||
break;
|
||||
|
||||
sbufWriteU16(dst, failsafeConfig()->failsafe_throttle);
|
||||
|
||||
#ifdef GPS
|
||||
sbufWriteU8(dst, gpsConfig()->provider); // gps_type
|
||||
sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
|
||||
sbufWriteU8(dst, gpsConfig()->sbasMode); // gps_ubx_sbas
|
||||
#else
|
||||
sbufWriteU8(dst, 0); // gps_type
|
||||
sbufWriteU8(dst, 0); // TODO gps_baudrate (an index, cleanflight uses a uint32_t
|
||||
sbufWriteU8(dst, 0); // gps_ubx_sbas
|
||||
#endif
|
||||
sbufWriteU8(dst, 0); // was multiwiiCurrentMeterOutput
|
||||
sbufWriteU8(dst, rxConfig()->rssi_channel);
|
||||
sbufWriteU8(dst, 0);
|
||||
|
||||
#ifdef MAG
|
||||
case MSP_COMPASS_CONFIG:
|
||||
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
|
||||
|
||||
sbufWriteU8(dst, 0); // was vbatscale
|
||||
sbufWriteU8(dst, batteryConfig()->vbatmincellvoltage);
|
||||
sbufWriteU8(dst, batteryConfig()->vbatmaxcellvoltage);
|
||||
sbufWriteU8(dst, batteryConfig()->vbatwarningcellvoltage);
|
||||
break;
|
||||
|
||||
case MSP_MOTOR_PINS:
|
||||
// FIXME This is hardcoded and should not be.
|
||||
for (int i = 0; i < 8; i++) {
|
||||
sbufWriteU8(dst, i + 1);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef GPS
|
||||
case MSP_GPS_CONFIG:
|
||||
sbufWriteU8(dst, gpsConfig()->provider); // gps_type
|
||||
sbufWriteU8(dst, gpsConfig()->sbasMode); // gps_ubx_sbas
|
||||
break;
|
||||
|
||||
case MSP_RAW_GPS:
|
||||
sbufWriteU8(dst, STATE(GPS_FIX));
|
||||
sbufWriteU8(dst, GPS_numSat);
|
||||
|
@ -886,7 +854,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
}
|
||||
break;
|
||||
|
||||
// Additional commands that are not compatible with MultiWii
|
||||
case MSP_ACC_TRIM:
|
||||
sbufWriteU16(dst, accelerometerConfig()->accelerometerTrims.values.pitch);
|
||||
sbufWriteU16(dst, accelerometerConfig()->accelerometerTrims.values.roll);
|
||||
|
@ -898,11 +865,11 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU32(dst, U_ID_2);
|
||||
break;
|
||||
|
||||
case MSP_FEATURE:
|
||||
case MSP_FEATURE_CONFIG:
|
||||
sbufWriteU32(dst, featureMask());
|
||||
break;
|
||||
|
||||
case MSP_BOARD_ALIGNMENT:
|
||||
case MSP_BOARD_ALIGNMENT_CONFIG:
|
||||
sbufWriteU16(dst, boardAlignment()->rollDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->pitchDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->yawDegrees);
|
||||
|
@ -1002,7 +969,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteU8(dst, batteryConfig()->currentMeterSource);
|
||||
break;
|
||||
|
||||
case MSP_MIXER:
|
||||
case MSP_MIXER_CONFIG:
|
||||
sbufWriteU8(dst, mixerConfig()->mixerMode);
|
||||
break;
|
||||
|
||||
|
@ -1047,21 +1014,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
sbufWriteData(dst, rxConfig()->rcmap, MAX_MAPPABLE_RX_INPUTS);
|
||||
break;
|
||||
|
||||
case MSP_BF_CONFIG:
|
||||
sbufWriteU8(dst, mixerConfig()->mixerMode);
|
||||
|
||||
sbufWriteU32(dst, featureMask());
|
||||
|
||||
sbufWriteU8(dst, rxConfig()->serialrx_provider);
|
||||
|
||||
sbufWriteU16(dst, boardAlignment()->rollDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->pitchDegrees);
|
||||
sbufWriteU16(dst, boardAlignment()->yawDegrees);
|
||||
|
||||
sbufWriteU16(dst, 0); // was currentMeterScale, see MSP_CURRENT_METER_CONFIG
|
||||
sbufWriteU16(dst, 0); //was currentMeterOffset, see MSP_CURRENT_METER_CONFIG
|
||||
break;
|
||||
|
||||
case MSP_CF_SERIAL_CONFIG:
|
||||
for (int i = 0; i < SERIAL_PORT_COUNT; i++) {
|
||||
if (!serialIsPortAvailable(serialConfig()->portConfigs[i].identifier)) {
|
||||
|
@ -1169,13 +1121,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
|
|||
#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:
|
||||
case MSP_MOTOR_3D_CONFIG:
|
||||
sbufWriteU16(dst, flight3DConfig()->deadband3d_low);
|
||||
sbufWriteU16(dst, flight3DConfig()->deadband3d_high);
|
||||
sbufWriteU16(dst, flight3DConfig()->neutral3d);
|
||||
|
@ -1359,9 +1305,11 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_HEAD:
|
||||
#if defined(GPS) || defined(MAG)
|
||||
case MSP_SET_HEADING:
|
||||
magHold = sbufReadU16(src);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP_SET_RAW_RC:
|
||||
#ifdef USE_RX_MSP
|
||||
|
@ -1388,10 +1336,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
armingConfigMutable()->disarm_kill_switch = sbufReadU8(src);
|
||||
break;
|
||||
|
||||
case MSP_SET_LOOP_TIME:
|
||||
sbufReadU16(src);
|
||||
break;
|
||||
|
||||
case MSP_SET_PID_CONTROLLER:
|
||||
break;
|
||||
|
||||
|
@ -1470,37 +1414,27 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_MISC:
|
||||
rxConfigMutable()->midrc = sbufReadU16(src);
|
||||
case MSP_SET_MOTOR_CONFIG:
|
||||
motorConfigMutable()->minthrottle = sbufReadU16(src);
|
||||
motorConfigMutable()->maxthrottle = sbufReadU16(src);
|
||||
motorConfigMutable()->mincommand = sbufReadU16(src);
|
||||
|
||||
failsafeConfigMutable()->failsafe_throttle = sbufReadU16(src);
|
||||
|
||||
#ifdef GPS
|
||||
gpsConfigMutable()->provider = sbufReadU8(src); // gps_type
|
||||
sbufReadU8(src); // gps_baudrate
|
||||
gpsConfigMutable()->sbasMode = sbufReadU8(src); // gps_ubx_sbas
|
||||
#else
|
||||
sbufReadU8(src); // gps_type
|
||||
sbufReadU8(src); // gps_baudrate
|
||||
sbufReadU8(src); // gps_ubx_sbas
|
||||
#endif
|
||||
sbufReadU8(src); // legacy - was multiwiiCurrentMeterOutput
|
||||
rxConfigMutable()->rssi_channel = sbufReadU8(src);
|
||||
sbufReadU8(src);
|
||||
|
||||
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
|
||||
|
||||
sbufReadU8(src); // legacy - was vbatscale
|
||||
batteryConfigMutable()->vbatmincellvoltage = sbufReadU8(src); // vbatlevel_warn1 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatmaxcellvoltage = sbufReadU8(src); // vbatlevel_warn2 in MWC2.3 GUI
|
||||
batteryConfigMutable()->vbatwarningcellvoltage = sbufReadU8(src); // vbatlevel when buzzer starts to alert
|
||||
break;
|
||||
|
||||
#ifdef GPS
|
||||
case MSP_SET_GPS_CONFIG:
|
||||
gpsConfigMutable()->provider = sbufReadU8(src); // gps_type
|
||||
gpsConfigMutable()->sbasMode = sbufReadU8(src); // gps_ubx_sbas
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MAG
|
||||
case MSP_SET_COMPASS_CONFIG:
|
||||
compassConfigMutable()->mag_declination = sbufReadU16(src) * 10;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MSP_SET_MOTOR:
|
||||
for (int i = 0; i < 8; i++) { // FIXME should this use MAX_MOTORS or MAX_SUPPORTED_MOTORS instead of 8
|
||||
for (int i = 0; i < getMotorCount(); i++) {
|
||||
motor_disarmed[i] = convertExternalToMotor(sbufReadU16(src));
|
||||
}
|
||||
break;
|
||||
|
@ -1544,7 +1478,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
#endif
|
||||
break;
|
||||
|
||||
case MSP_SET_3D:
|
||||
case MSP_SET_MOTOR_3D_CONFIG:
|
||||
flight3DConfigMutable()->deadband3d_low = sbufReadU16(src);
|
||||
flight3DConfigMutable()->deadband3d_high = sbufReadU16(src);
|
||||
flight3DConfigMutable()->neutral3d = sbufReadU16(src);
|
||||
|
@ -1821,12 +1755,12 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
}
|
||||
break;
|
||||
#endif
|
||||
case MSP_SET_FEATURE:
|
||||
case MSP_SET_FEATURE_CONFIG:
|
||||
featureClearAll();
|
||||
featureSet(sbufReadU32(src)); // features bitmap
|
||||
break;
|
||||
|
||||
case MSP_SET_BOARD_ALIGNMENT:
|
||||
case MSP_SET_BOARD_ALIGNMENT_CONFIG:
|
||||
boardAlignmentMutable()->rollDegrees = sbufReadU16(src);
|
||||
boardAlignmentMutable()->pitchDegrees = sbufReadU16(src);
|
||||
boardAlignmentMutable()->yawDegrees = sbufReadU16(src);
|
||||
|
@ -1885,11 +1819,13 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
batteryConfigMutable()->currentMeterSource = sbufReadU8(src);
|
||||
break;
|
||||
|
||||
case MSP_SET_MIXER_CONFIG:
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
case MSP_SET_MIXER:
|
||||
mixerConfigMutable()->mixerMode = sbufReadU8(src);
|
||||
break;
|
||||
#else
|
||||
sbufReadU8(src);
|
||||
#endif
|
||||
break;
|
||||
|
||||
case MSP_SET_RX_CONFIG:
|
||||
rxConfigMutable()->serialrx_provider = sbufReadU8(src);
|
||||
|
@ -1945,26 +1881,6 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
}
|
||||
break;
|
||||
|
||||
case MSP_SET_BF_CONFIG:
|
||||
#ifdef USE_QUAD_MIXER_ONLY
|
||||
sbufReadU8(src); // mixerMode ignored
|
||||
#else
|
||||
mixerConfigMutable()->mixerMode = sbufReadU8(src); // mixerMode
|
||||
#endif
|
||||
|
||||
featureClearAll();
|
||||
featureSet(sbufReadU32(src)); // features bitmap
|
||||
|
||||
rxConfigMutable()->serialrx_provider = sbufReadU8(src); // serialrx_type
|
||||
|
||||
boardAlignmentMutable()->rollDegrees = sbufReadU16(src); // board_align_roll
|
||||
boardAlignmentMutable()->pitchDegrees = sbufReadU16(src); // board_align_pitch
|
||||
boardAlignmentMutable()->yawDegrees = sbufReadU16(src); // board_align_yaw
|
||||
|
||||
sbufReadU16(src); // was currentMeterScale, see MSP_SET_CURRENT_METER_CONFIG
|
||||
sbufReadU16(src); // was currentMeterOffset see MSP_SET_CURRENT_METER_CONFIG
|
||||
break;
|
||||
|
||||
case MSP_SET_CF_SERIAL_CONFIG:
|
||||
{
|
||||
uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4);
|
||||
|
|
|
@ -111,17 +111,17 @@
|
|||
#define MSP_MODE_RANGES 34 //out message Returns all mode ranges
|
||||
#define MSP_SET_MODE_RANGE 35 //in message Sets a single mode range
|
||||
|
||||
#define MSP_FEATURE 36
|
||||
#define MSP_SET_FEATURE 37
|
||||
#define MSP_FEATURE_CONFIG 36
|
||||
#define MSP_SET_FEATURE_CONFIG 37
|
||||
|
||||
#define MSP_BOARD_ALIGNMENT 38
|
||||
#define MSP_SET_BOARD_ALIGNMENT 39
|
||||
#define MSP_BOARD_ALIGNMENT_CONFIG 38
|
||||
#define MSP_SET_BOARD_ALIGNMENT_CONFIG 39
|
||||
|
||||
#define MSP_CURRENT_METER_CONFIG 40
|
||||
#define MSP_SET_CURRENT_METER_CONFIG 41
|
||||
|
||||
#define MSP_MIXER 42
|
||||
#define MSP_SET_MIXER 43
|
||||
#define MSP_MIXER_CONFIG 42
|
||||
#define MSP_SET_MIXER_CONFIG 43
|
||||
|
||||
#define MSP_RX_CONFIG 44
|
||||
#define MSP_SET_RX_CONFIG 45
|
||||
|
@ -159,23 +159,22 @@
|
|||
#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
|
||||
// Use more specific commands, e.g. MSP_FEATURE_CONFIG, MSP_BATTERY_CONFIG, etc.
|
||||
// DEPRECATED -#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere
|
||||
// DEPRECATED -#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
|
||||
|
||||
// Use MSP_BUILD_INFO instead
|
||||
// DEPRECATED - #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
|
||||
|
||||
#define MSP_LOOP_TIME 73 //out message Returns FC cycle time i.e looptime parameter
|
||||
#define MSP_SET_LOOP_TIME 74 //in message Sets FC cycle time i.e looptime parameter
|
||||
// No-longer needed
|
||||
// DEPRECATED - #define MSP_LOOP_TIME 73 //out message Returns FC cycle time i.e looptime parameter // DEPRECATED
|
||||
// DEPRECATED - #define MSP_SET_LOOP_TIME 74 //in message Sets FC cycle time i.e looptime parameter // DEPRECATED
|
||||
|
||||
#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
|
||||
|
@ -226,8 +225,8 @@
|
|||
// 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
|
||||
// See MSP_API_VERSION and MSP_MIXER_CONFIG
|
||||
//DEPRECATED - #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
|
||||
|
@ -242,9 +241,12 @@
|
|||
#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_BOX 113 //out message BOX setup (number is dependant of your setup)
|
||||
#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
|
||||
// Legacy Multiicommand that was never used.
|
||||
//DEPRECATED - #define MSP_BOX 113 //out message BOX setup (number is dependant of your setup)
|
||||
// Legacy command that was under constant change due to the naming vagueness, avoid at all costs - use more specific commands instead.
|
||||
//DEPRECATED - #define MSP_MISC 114 //out message powermeter trig
|
||||
// Legacy Multiicommand that was never used and always wrong
|
||||
//DEPRECATED - #define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI
|
||||
#define MSP_BOXNAMES 116 //out message the aux switch names
|
||||
#define MSP_PIDNAMES 117 //out message the PID names
|
||||
#define MSP_WP 118 //out message get a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold
|
||||
|
@ -252,34 +254,42 @@
|
|||
#define MSP_SERVO_CONFIGURATIONS 120 //out message All servo configurations.
|
||||
#define MSP_NAV_STATUS 121 //out message Returns navigation status
|
||||
#define MSP_NAV_CONFIG 122 //out message Returns navigation parameters
|
||||
#define MSP_3D 124 //out message Settings needed for reversible ESCs
|
||||
#define MSP_MOTOR_3D_CONFIG 124 //out message Settings needed for reversible ESCs
|
||||
#define MSP_RC_DEADBAND 125 //out message deadbands for yaw alt pitch roll
|
||||
#define MSP_SENSOR_ALIGNMENT 126 //out message orientation of acc,gyro,mag
|
||||
#define MSP_LED_STRIP_MODECOLOR 127 //out message Get LED strip mode_color settings
|
||||
#define MSP_VOLTAGE_METERS 128 //out message Voltage (per meter)
|
||||
#define MSP_CURRENT_METERS 129 //out message Amperage (per meter)
|
||||
#define MSP_BATTERY_STATE 130 //out message Connected/Disconnected, Voltage, Current Used
|
||||
#define MSP_MOTOR_CONFIG 131 //out message Motor configuration (min/max throttle, etc)
|
||||
#define MSP_GPS_CONFIG 132 //out message GPS configuration
|
||||
#define MSP_COMPASS_CONFIG 133 //out message Compass configuration
|
||||
|
||||
#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)
|
||||
// Legacy multiiwii command that was never used.
|
||||
//DEPRECATED - #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
|
||||
#define MSP_MAG_CALIBRATION 206 //in message no param
|
||||
#define MSP_SET_MISC 207 //in message powermeter trig + 8 free for future use
|
||||
// Legacy command that was under constant change due to the naming vagueness, avoid at all costs - use more specific commands instead.
|
||||
//DEPRECATED - #define MSP_SET_MISC 207 //in message powermeter trig + 8 free for future use
|
||||
#define MSP_RESET_CONF 208 //in message no param
|
||||
#define MSP_SET_WP 209 //in message sets a given WP (WP#,lat, lon, alt, flags)
|
||||
#define MSP_SELECT_SETTING 210 //in message Select Setting Number (0-2)
|
||||
#define MSP_SET_HEAD 211 //in message define a new heading hold direction
|
||||
#define MSP_SET_HEADING 211 //in message define a new heading hold direction
|
||||
#define MSP_SET_SERVO_CONFIGURATION 212 //in message Servo settings
|
||||
#define MSP_SET_MOTOR 214 //in message PropBalance function
|
||||
#define MSP_SET_NAV_CONFIG 215 //in message Sets nav config parameters - write to the eeprom
|
||||
#define MSP_SET_3D 217 //in message Settings needed for reversible ESCs
|
||||
#define MSP_SET_MOTOR_3D_CONFIG 217 //in message Settings needed for reversible ESCs
|
||||
#define MSP_SET_RC_DEADBAND 218 //in message deadbands for yaw alt pitch roll
|
||||
#define MSP_SET_RESET_CURR_PID 219 //in message resetting the current pid profile to defaults
|
||||
#define MSP_SET_SENSOR_ALIGNMENT 220 //in message set the orientation of the acc,gyro,mag
|
||||
#define MSP_SET_LED_STRIP_MODECOLOR 221 //in message Set LED strip mode_color settings
|
||||
#define MSP_SET_MOTOR_CONFIG 222 //out message Motor configuration (min/max throttle, etc)
|
||||
#define MSP_SET_GPS_CONFIG 223 //out message GPS configuration
|
||||
#define MSP_SET_COMPASS_CONFIG 224 //out message Compass configuration
|
||||
|
||||
// #define MSP_BIND 240 //in message no param
|
||||
// #define MSP_ALARMS 242
|
||||
|
|
|
@ -17,22 +17,15 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define TBS_CORE_PNP_PRO 0x80
|
||||
#define RESERVED 0x8A
|
||||
#define PNP_PRO_DIDITAL_CURRENT_SENSOR 0xC0
|
||||
#define PNP_PRO_GPS 0xC2
|
||||
#define TSB_BLACKBOX 0xC4
|
||||
#define CLEANFLIGHT_FC 0xC8
|
||||
#define CROSSFIRE_UHF_RECEIVER 0xEC
|
||||
#define BST_BUFFER_SIZE 128
|
||||
|
||||
#define GPS_POSITION_FRAME_ID 0x02
|
||||
#define GPS_TIME_FRAME_ID 0x03
|
||||
#define FC_ATTITUDE_FRAME_ID 0x1E
|
||||
#define RC_CHANNEL_FRAME_ID 0x15
|
||||
#define CROSSFIRE_RSSI_FRAME_ID 0x14
|
||||
#define CLEANFLIGHT_MODE_FRAME_ID 0x20
|
||||
|
||||
#define DATA_BUFFER_SIZE 128
|
||||
#define I2C_ADDR_TBS_CORE_PNP_PRO 0x80
|
||||
#define I2C_ADDR_RESERVED 0x8A
|
||||
#define I2C_ADDR_PNP_PRO_DIDITAL_CURRENT_SENSOR 0xC0
|
||||
#define I2C_ADDR_PNP_PRO_GPS 0xC2
|
||||
#define I2C_ADDR_TSB_BLACKBOX 0xC4
|
||||
#define I2C_ADDR_CROSSFIRE_UHF_RECEIVER 0xEC
|
||||
#define I2C_ADDR_CLEANFLIGHT_FC 0xC8
|
||||
|
||||
typedef enum BSTDevice {
|
||||
BSTDEV_1,
|
||||
|
|
|
@ -60,17 +60,17 @@ volatile bool coreProReady = false;
|
|||
// BST TimeoutUserCallback
|
||||
///////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
uint8_t dataBuffer[DATA_BUFFER_SIZE] = {0};
|
||||
uint8_t dataBuffer[BST_BUFFER_SIZE] = {0};
|
||||
uint8_t dataBufferPointer = 0;
|
||||
uint8_t bstWriteDataLen = 0;
|
||||
|
||||
uint32_t micros(void);
|
||||
|
||||
uint8_t writeData[DATA_BUFFER_SIZE] = {0};
|
||||
uint8_t writeData[BST_BUFFER_SIZE] = {0};
|
||||
uint8_t currentWriteBufferPointer = 0;
|
||||
bool receiverAddress = false;
|
||||
|
||||
uint8_t readData[DATA_BUFFER_SIZE] = {0};
|
||||
uint8_t readData[BST_BUFFER_SIZE] = {0};
|
||||
uint8_t bufferPointer = 0;
|
||||
|
||||
bool cleanflight_data_ready = false;
|
||||
|
@ -221,7 +221,7 @@ void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/)
|
|||
BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
BST_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
|
||||
BST_InitStructure.I2C_OwnAddress1 = I2C_ADDR_CLEANFLIGHT_FC;
|
||||
BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
|
@ -269,7 +269,7 @@ void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/)
|
|||
BST_InitStructure.I2C_Mode = I2C_Mode_I2C;
|
||||
BST_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
|
||||
BST_InitStructure.I2C_DigitalFilter = 0x00;
|
||||
BST_InitStructure.I2C_OwnAddress1 = CLEANFLIGHT_FC;
|
||||
BST_InitStructure.I2C_OwnAddress1 = I2C_ADDR_CLEANFLIGHT_FC;
|
||||
BST_InitStructure.I2C_Ack = I2C_Ack_Enable;
|
||||
BST_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
|
||||
BST_InitStructure.I2C_Timing = 0x30E0257A; // 100 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -23,6 +23,11 @@
|
|||
#include "drivers/dma.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#ifdef USE_BST
|
||||
#include "bus_bst.h"
|
||||
#endif
|
||||
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_PPM, 0, GPIO_AF_6, NULL, 0 }, // PWM1 - PA8
|
||||
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM2 - PC6
|
||||
|
@ -37,3 +42,12 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM11 - PB15
|
||||
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM11 - PB15
|
||||
};
|
||||
|
||||
|
||||
#ifdef USE_BST
|
||||
void targetBusInit(void)
|
||||
{
|
||||
bstInit(BST_DEVICE);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -22,9 +22,12 @@
|
|||
#define BST_DEVICE_NAME_LENGTH 12
|
||||
#define TARGET_CONFIG
|
||||
#define TARGET_VALIDATECONFIG
|
||||
#define TARGET_BUS_INIT
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
|
||||
|
||||
#undef USE_RX_MSP // never used.
|
||||
|
||||
#define LED0 PC15
|
||||
#define LED1 PC14
|
||||
#define LED2 PC13
|
||||
|
|
Loading…
Reference in New Issue