1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 01:05:27 +03:00

Changing all line endings to WINDOWS line endings (CR+LF) and removing all End-Of-Line whitespace and using spaces instead of tabs. Please ensure you configure your editors and tools to follow suit. If using git please enable autocrlf in your .git/config file.

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@393 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
dominicc1974@gmail.com 2013-09-06 23:14:48 +00:00
parent 929bbc8c3f
commit 4c191270bf
41 changed files with 2000 additions and 2000 deletions

View file

@ -1,7 +1,7 @@
#include "board.h"
#include "mw.h"
// Multiwii Serial Protocol 0
// Multiwii Serial Protocol 0
#define MSP_VERSION 0
#define PLATFORM_32BIT ((uint32_t)1 << 31)
@ -50,17 +50,17 @@
#define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4
// Additional commands that are not compatible with MultiWii
#define MSP_UID 160 //out message Unique device ID
#define MSP_ACC_TRIM 240 //out message get acc angle trim values
#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
#define MSP_GPSSVINFO 164 //out message get Signal Strength (only U-Blox)
#define INBUF_SIZE 64
#define MSP_UID 160 //out message Unique device ID
#define MSP_ACC_TRIM 240 //out message get acc angle trim values
#define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
#define MSP_GPSSVINFO 164 //out message get Signal Strength (only U-Blox)
#define INBUF_SIZE 64
struct box_t {
const uint8_t boxIndex; // this is from boxnames enum
const char *boxName; // GUI-readable box name
const uint8_t permanentId; //
const uint8_t permanentId; //
} boxes[] = {
{ BOXARM, "ARM;", 0 },
{ BOXANGLE, "ANGLE;", 1 },
@ -120,7 +120,7 @@ const uint8_t boxids[] = { // permanent IDs associated to boxes. This way,
4, // "VARIO;"
5, // "MAG;"
6, // "HEADFREE;"
7, // "HEADADJ;"
7, // "HEADADJ;"
8, // "CAMSTAB;"
9, // "CAMTRIG;"
10, // "GPS HOME;"
@ -251,7 +251,7 @@ void serializeBoxNamesReply(void)
strcat(buf, boxes[i].boxName);
}
}
headSerialReply(strlen(buf));
for (c = buf; *c; c++)
serialize8(*c);
@ -561,7 +561,7 @@ static void evaluateCommand(void)
serialize32(lon);
serialize32(AltHold); // altitude (cm) will come here -- temporary implementation to test feature with apps
serialize16(0); // heading will come here (deg)
serialize16(0); // time to stay (ms) will come here
serialize16(0); // time to stay (ms) will come here
serialize8(0); // nav flag will come here
break;
case MSP_SET_WP:
@ -625,22 +625,22 @@ static void evaluateCommand(void)
case MSP_UID:
headSerialReply(12);
serialize32(U_ID_0);
serialize32(U_ID_1);
serialize32(U_ID_2);
break;
case MSP_GPSSVINFO:
headSerialReply(1 + (GPS_numCh * 4));
serialize8(GPS_numCh);
for (i = 0; i < GPS_numCh; i++){
serialize8(GPS_svinfo_chn[i]);
serialize8(GPS_svinfo_svid[i]);
serialize8(GPS_svinfo_quality[i]);
serialize8(GPS_svinfo_cno[i]);
}
break;
default: // we do not know how to handle the (valid) message, indicate error MSP $M!
headSerialError(0);
break;
serialize32(U_ID_1);
serialize32(U_ID_2);
break;
case MSP_GPSSVINFO:
headSerialReply(1 + (GPS_numCh * 4));
serialize8(GPS_numCh);
for (i = 0; i < GPS_numCh; i++){
serialize8(GPS_svinfo_chn[i]);
serialize8(GPS_svinfo_svid[i]);
serialize8(GPS_svinfo_quality[i]);
serialize8(GPS_svinfo_cno[i]);
}
break;
default: // we do not know how to handle the (valid) message, indicate error MSP $M!
headSerialError(0);
break;
}
tailSerialReply();
}