1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

trashed uvop keil file since that was system-specific stuff.

applied mwc-dev GPS code with bits of tarducopter code by sbaron. Thanks again. Moved some of the GPS config stuff into cli - gps_lpf, min/max nav speed, nav_controls_heading. Remember I don't test any GPS functionality at all, so if this makes your quad fly towards North Korea at over 9000cm/sec, this is NOT my problem.
spacing fixes in a couple files.
trashed old serial code that was under #if 0


git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@161 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop 2012-06-06 15:09:44 +00:00
parent 12d6c41407
commit 19ca85963b
9 changed files with 6546 additions and 6853 deletions

View file

@ -1,35 +1,36 @@
#include "board.h"
#include "mw.h"
#define MSP_IDENT 100 //out message multitype + version
#define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation
#define MSP_RAW_IMU 102 //out message 9 DOF
#define MSP_SERVO 103 //out message 8 servos
#define MSP_MOTOR 104 //out message 8 motors
#define MSP_RC 105 //out message 8 rc chan
#define MSP_RAW_GPS 106 //out message fix, numsat, lat, lon, alt, speed
#define MSP_COMP_GPS 107 //out message distance home, direction home
#define MSP_ATTITUDE 108 //out message 2 angles 1 heading
#define MSP_ALTITUDE 109 //out message 1 altitude
#define MSP_BAT 110 //out message vbat, powermetersum
#define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
#define MSP_PID 112 //out message up to 16 P I D (8 are used)
#define MSP_BOX 113 //out message up to 16 checkbox (11 are used)
#define MSP_MISC 114 //out message powermeter trig + 8 free for future use
#define MSP_IDENT 100 //out message multitype + version
#define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation
#define MSP_RAW_IMU 102 //out message 9 DOF
#define MSP_SERVO 103 //out message 8 servos
#define MSP_MOTOR 104 //out message 8 motors
#define MSP_RC 105 //out message 8 rc chan
#define MSP_RAW_GPS 106 //out message fix, numsat, lat, lon, alt, speed
#define MSP_COMP_GPS 107 //out message distance home, direction home
#define MSP_ATTITUDE 108 //out message 2 angles 1 heading
#define MSP_ALTITUDE 109 //out message 1 altitude
#define MSP_BAT 110 //out message vbat, powermetersum
#define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
#define MSP_PID 112 //out message up to 16 P I D (8 are used)
#define MSP_BOX 113 //out message up to 16 checkbox (11 are used)
#define MSP_MISC 114 //out message powermeter trig + 8 free for future use
#define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI
#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 up to 16 P I D (8 are used)
#define MSP_SET_BOX 203 //in message up to 16 checkbox (11 are used)
#define MSP_SET_RC_TUNING 204 //in message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
#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
#define MSP_RESET_CONF 208 //in message no param
#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 up to 16 P I D (8 are used)
#define MSP_SET_BOX 203 //in message up to 16 checkbox (11 are used)
#define MSP_SET_RC_TUNING 204 //in message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
#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
#define MSP_RESET_CONF 208 //in message no param
#define MSP_EEPROM_WRITE 250 //in message no param
#define MSP_EEPROM_WRITE 250 //in message no param
#define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4
#define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4
static uint8_t checksum, stateMSP, indRX, inBuf[64];
@ -70,16 +71,16 @@ void serialize8(uint8_t a)
uint32_t read32(void)
{
uint32_t t = inBuf[indRX++];
t+= inBuf[indRX++] << 8;
t+= (uint32_t)inBuf[indRX++] << 16;
t+= (uint32_t)inBuf[indRX++] << 24;
t += inBuf[indRX++] << 8;
t += (uint32_t) inBuf[indRX++] << 16;
t += (uint32_t) inBuf[indRX++] << 24;
return t;
}
uint16_t read16(void)
{
uint16_t t = inBuf[indRX++];
t+= inBuf[indRX++] << 8;
t += inBuf[indRX++] << 8;
return t;
}
@ -143,8 +144,8 @@ void serialCom(void)
case MSP_SET_RAW_GPS:
GPS_fix = read8();
GPS_numSat = read8();
GPS_latitude = read32();
GPS_longitude = read32();
GPS_coord[LAT] = read32();
GPS_coord[LON] = read32();
GPS_altitude = read16();
GPS_speed = read16();
GPS_update = 1;
@ -200,7 +201,7 @@ void serialCom(void)
case MSP_IDENT: // and we check message code to execute the relative code
headSerialReply(c, 2); // we reply with an header indicating a payload lenght of 2 octets
serialize8(VERSION); // the first octet. serialize8/16/32 is used also to compute a checksum
serialize8(cfg.mixerConfiguration); // the second one
serialize8(cfg.mixerConfiguration); // the second one
tailSerialReply();
break; // mainly to send the last octet which is the checksum
case MSP_STATUS:
@ -243,8 +244,8 @@ void serialCom(void)
headSerialReply(c, 14);
serialize8(GPS_fix);
serialize8(GPS_numSat);
serialize32(GPS_latitude);
serialize32(GPS_longitude);
serialize32(GPS_coord[LAT]);
serialize32(GPS_coord[LON]);
serialize16(GPS_altitude);
serialize16(GPS_speed);
tailSerialReply();
@ -306,6 +307,12 @@ void serialCom(void)
serialize16(0);
tailSerialReply();
break;
case MSP_MOTOR_PINS:
headSerialReply(c, 8);
for (i = 0; i < 8; i++)
serialize8(i + 1);
tailSerialReply();
break;
case MSP_RESET_CONF:
checkFirstTime(true);
break;
@ -351,148 +358,7 @@ void serialCom(void)
if (c == '#')
cliProcess();
else if (c == 'R')
systemReset(true); // reboot to bootloader
systemReset(true); // reboot to bootloader
}
}
}
#if 0
void oldSserialCom(void)
{
uint8_t i;
// in cli mode, all uart stuff goes to here. enter cli mode by sending #
if (cliMode) {
cliProcess();
return;
}
if (uartAvailable()) {
switch (uartRead()) {
case '#':
cliProcess();
break;
#ifdef BTSERIAL
case 'K': // receive RC data from Bluetooth Serial adapter as a remote
rcData[THROTTLE] = (SerialRead(0) * 4) + 1000;
rcData[ROLL] = (SerialRead(0) * 4) + 1000;
rcData[PITCH] = (SerialRead(0) * 4) + 1000;
rcData[YAW] = (SerialRead(0) * 4) + 1000;
rcData[AUX1] = (SerialRead(0) * 4) + 1000;
break;
#endif
case 'M': // Multiwii @ arduino to GUI all data
serialize8('M');
serialize8(VERSION); // MultiWii Firmware version
for (i = 0; i < 3; i++)
serialize16(accSmooth[i]);
for (i = 0; i < 3; i++)
serialize16(gyroData[i]);
for (i = 0; i < 3; i++)
serialize16(magADC[i]);
serialize16(EstAlt / 10);
serialize16(heading); // compass
for (i = 0; i < 8; i++)
serialize16(servo[i]);
for (i = 0; i < 8; i++)
serialize16(motor[i]);
for (i = 0; i < 8; i++)
serialize16(rcData[i]);
serialize8(sensors(SENSOR_ACC) << 1 | sensors(SENSOR_BARO) << 2 | sensors(SENSOR_MAG) << 3 | sensors(SENSOR_GPS) << 4);
serialize8(accMode | baroMode << 1 | magMode << 2 | GPSModeHome << 3 | GPSModeHold << 4 | armed << 5);
#if defined(LOG_VALUES)
serialize16(cycleTimeMax);
cycleTimeMax = 0;
#else
serialize16(cycleTime);
#endif
serialize16(i2cGetErrorCounter());
for (i = 0; i < 2; i++)
serialize16(angle[i]);
serialize8(cfg.mixerConfiguration);
for (i = 0; i < PIDITEMS; i++) {
serialize8(cfg.P8[i]);
serialize8(cfg.I8[i]);
serialize8(cfg.D8[i]);
}
serialize8(cfg.rcRate8);
serialize8(cfg.rcExpo8);
serialize8(cfg.rollPitchRate);
serialize8(cfg.yawRate);
serialize8(cfg.dynThrPID);
for (i = 0; i < CHECKBOXITEMS; i++)
serialize16(cfg.activate[i]);
serialize16(GPS_distanceToHome);
serialize16(GPS_directionToHome + 180);
serialize8(GPS_numSat);
serialize8(GPS_fix);
serialize8(GPS_update);
serialize16(0); // power meter, removed
serialize16(0); // power meter, removed
serialize8(vbat);
serialize16(BaroAlt / 10); // 4 variables are here for general monitoring purpose
serialize16(debug2); // debug2
serialize16(debug3); // debug3
serialize16(debug4); // debug4
serialize8('M');
break;
case 'O': // arduino to OSD data - contribution from MIS
serialize8('O');
for (i = 0; i < 3; i++)
serialize16(accSmooth[i]);
for (i = 0; i < 3; i++)
serialize16(gyroData[i]);
serialize16(EstAlt * 10.0f);
serialize16(heading); // compass - 16 bytes
for (i = 0; i < 2; i++)
serialize16(angle[i]); //20
for (i = 0; i < 6; i++)
serialize16(motor[i]); //32
for (i = 0; i < 6; i++) {
serialize16(rcData[i]);
} //44
serialize8(sensors(SENSOR_ACC) << 1 | sensors(SENSOR_BARO) << 2 | sensors(SENSOR_MAG) << 3 | sensors(SENSOR_GPS) << 4);
serialize8(accMode | baroMode << 1 | magMode << 2 | GPSModeHome << 3 | GPSModeHold << 4 | armed << 5);
serialize8(vbat); // Vbatt 47
serialize8(VERSION); // MultiWii Firmware version
serialize8(GPS_fix); // Fix indicator for OSD
serialize8(GPS_numSat);
serialize16(GPS_latitude);
serialize16(GPS_latitude >> 16);
serialize16(GPS_longitude);
serialize16(GPS_longitude >> 16);
serialize16(GPS_altitude);
serialize16(GPS_speed); // Speed for OSD
serialize8('O'); // NOT 49 anymore
break;
case 'R': // reboot to bootloader (oops, apparently this w as used for other trash, fix later)
systemReset(true);
break;
case 'W': //GUI write params to eeprom @ arduino
// while (uartAvailable() < (7 + 3 * PIDITEMS + 2 * CHECKBOXITEMS)) { }
for (i = 0; i < PIDITEMS; i++) {
cfg.P8[i] = uartReadPoll();
cfg.I8[i] = uartReadPoll();
cfg.D8[i] = uartReadPoll();
}
cfg.rcRate8 = uartReadPoll();
cfg.rcExpo8 = uartReadPoll(); //2
cfg.rollPitchRate = uartReadPoll();
cfg.yawRate = uartReadPoll(); //4
cfg.dynThrPID = uartReadPoll(); //5
for (i = 0; i < CHECKBOXITEMS; i++)
cfg.activate[i] = uartReadPoll();
uartReadPoll(); // power meter crap, removed
uartReadPoll(); // power meter crap, removed
writeParams(0);
break;
case 'S': // GUI to arduino ACC calibration request
calibratingA = 400;
break;
case 'E': // GUI to arduino MAG calibration request
calibratingM = 1;
break;
}
}
}
#endif