mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Xbee/Ser0 telemetry ports are working again
git-svn-id: https://arducopter.googlecode.com/svn/trunk@682 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
455e315a1a
commit
35b754bbae
@ -76,6 +76,7 @@ TODO:
|
||||
#define SERIAL3_BAUD 115200
|
||||
|
||||
#ifdef SerXbee // Xbee/Telemetry port
|
||||
//#define SerBau 115200 // Baud setting moved close next to port selection
|
||||
#define SerPri Serial3.print
|
||||
#define SerPrln Serial3.println
|
||||
#define SerRea Serial3.read
|
||||
@ -86,11 +87,8 @@ TODO:
|
||||
#define SerPor "FTDI"
|
||||
#endif
|
||||
|
||||
#ifndef SerPri // If we don't have SerPri set yet, it means we have are using Serial0
|
||||
#define SerUSB
|
||||
#endif
|
||||
|
||||
#ifdef SerUSB // Defines for normal Serial0 port
|
||||
#ifndef SerXbee // If we don't have SerXbee set, it means we have are using Serial0
|
||||
//#define SerBau 115200 // Baud setting moved close next to port selection
|
||||
#define SerPri Serial.print
|
||||
#define SerPrln Serial.println
|
||||
#define SerRea Serial.read
|
||||
|
@ -45,25 +45,41 @@
|
||||
//#define IsGPS // Do we have a GPS connected
|
||||
//#define IsNEWMTEK // Do we have MTEK with new firmware
|
||||
//#define IsMAG // Do we have a Magnetometer connected, if have remember to activate it from Configurator
|
||||
//#define IsTEL // Do we have a telemetry connected, eg. XBee connected on Telemetry port
|
||||
//#define IsAM // Do we have motormount LED's. AM = Atraction Mode
|
||||
//LEGACY-jp #define IsTEL // Do we have a telemetry connected, eg. XBee connected on Telemetry port
|
||||
#define IsAM // Do we have motormount LED's. AM = Atraction Mode
|
||||
|
||||
//#define UseAirspeed
|
||||
|
||||
//#define UseBMP
|
||||
//#define BATTERY_EVENT 1 // (boolean) 0 = don't read battery, 1 = read battery voltage (only if you have it wired up!)
|
||||
|
||||
//#define BATTERY_EVENT 1 // (boolean) 0 = don't read battery, 1 = read battery voltage (only if you have it _wired_ up!)
|
||||
|
||||
#define CONFIGURATOR
|
||||
|
||||
|
||||
////////////////////
|
||||
// Telemetry
|
||||
|
||||
// Serial data, do we have FTDI cable or Xbee on Telemetry port as our primary command link
|
||||
// If we are using normal FTDI/USB port as our telemetry/configuration, comment out next line
|
||||
// If we are using normal FTDI/USB port as our telemetry/configuration, disable next
|
||||
//#define SerXbee
|
||||
|
||||
//#define Ser0 // FTDI/USB Port Either one
|
||||
//#define Ser3 // Telemetry port
|
||||
// Telemetry port speed, default is 115200
|
||||
#define SerBau 115200
|
||||
|
||||
|
||||
|
||||
//////////////////////
|
||||
// Flight orientation
|
||||
|
||||
// Frame build condiguration
|
||||
#define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration
|
||||
//#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/* ************************************************************ */
|
||||
/* **************** MAIN PROGRAM - INCLUDES ******************* */
|
||||
/* ************************************************************ */
|
||||
@ -92,6 +108,7 @@
|
||||
/* Software version */
|
||||
#define VER 1.5 // Current software version (only numeric values)
|
||||
|
||||
|
||||
/* ************************************************************ */
|
||||
/* ************* MAIN PROGRAM - DECLARATIONS ****************** */
|
||||
/* ************************************************************ */
|
||||
@ -266,5 +283,27 @@ void loop()
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// AM and Mode status LED lights
|
||||
if(millis() - gled_timer > gled_speed) {
|
||||
gled_timer = millis();
|
||||
if(gled_status == HIGH) {
|
||||
digitalWrite(LED_Green, LOW);
|
||||
#ifdef IsAM
|
||||
digitalWrite(RE_LED, LOW);
|
||||
#endif
|
||||
gled_status = LOW;
|
||||
// SerPrln("L");
|
||||
}
|
||||
else {
|
||||
digitalWrite(LED_Green, HIGH);
|
||||
#ifdef IsAM
|
||||
if(motorArmed) digitalWrite(RE_LED, HIGH);
|
||||
#endif
|
||||
gled_status = HIGH;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
@ -61,7 +61,7 @@ void send_message(byte severity, const char *str) // This is the instance of se
|
||||
void readSerialCommand() {
|
||||
// Check for serial message
|
||||
if (SerAva()) {
|
||||
|
||||
queryType = SerRea();
|
||||
switch (queryType) {
|
||||
case 'A': // Stable PID
|
||||
KP_QUAD_ROLL = readFloatSerial();
|
||||
@ -351,6 +351,20 @@ void sendSerialTelemetry() {
|
||||
SerPri(read_adc(3));
|
||||
comma();
|
||||
SerPrln(read_adc(5));
|
||||
/* comma();
|
||||
SerPri(APM_Compass.Heading, 4);
|
||||
comma();
|
||||
SerPri(APM_Compass.Heading_X, 4);
|
||||
comma();
|
||||
SerPri(APM_Compass.Heading_Y, 4);
|
||||
comma();
|
||||
SerPri(APM_Compass.Mag_X);
|
||||
comma();
|
||||
SerPri(APM_Compass.Mag_Y);
|
||||
comma();
|
||||
SerPri(APM_Compass.Mag_Z);
|
||||
comma();
|
||||
*/
|
||||
break;
|
||||
case 'T': // Spare
|
||||
break;
|
||||
@ -438,3 +452,4 @@ float readFloatSerial() {
|
||||
while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128));
|
||||
return atof(data);
|
||||
}
|
||||
|
||||
|
@ -85,9 +85,14 @@ void APM_Init() {
|
||||
|
||||
DataFlash.StartWrite(1); // Start a write session on page 1
|
||||
|
||||
Serial.begin(115200);
|
||||
// Serial.begin(115200); // Old mode serial begin, remove soon, by jp/17-10-10
|
||||
|
||||
//Serial.println("ArduCopter Quadcopter v1.0");
|
||||
|
||||
// Proper Serial port/baud are defined on main .pde and then Arducopter.h with
|
||||
// Choises of Xbee or
|
||||
SerBeg(SerBau);
|
||||
|
||||
// Check if we enable the DataFlash log Read Mode (switch)
|
||||
// If we press switch 1 at startup we read the Dataflash eeprom
|
||||
while (digitalRead(SW1_pin)==0)
|
||||
@ -126,5 +131,6 @@ void APM_Init() {
|
||||
digitalWrite(RI_LED, HIGH);
|
||||
digitalWrite(LE_LED, HIGH);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user