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:
jphelirc 2010-10-17 17:34:17 +00:00
parent 455e315a1a
commit 35b754bbae
4 changed files with 199 additions and 141 deletions

View File

@ -76,6 +76,7 @@ TODO:
#define SERIAL3_BAUD 115200 #define SERIAL3_BAUD 115200
#ifdef SerXbee // Xbee/Telemetry port #ifdef SerXbee // Xbee/Telemetry port
//#define SerBau 115200 // Baud setting moved close next to port selection
#define SerPri Serial3.print #define SerPri Serial3.print
#define SerPrln Serial3.println #define SerPrln Serial3.println
#define SerRea Serial3.read #define SerRea Serial3.read
@ -86,11 +87,8 @@ TODO:
#define SerPor "FTDI" #define SerPor "FTDI"
#endif #endif
#ifndef SerPri // If we don't have SerPri set yet, it means we have are using Serial0 #ifndef SerXbee // If we don't have SerXbee set, it means we have are using Serial0
#define SerUSB //#define SerBau 115200 // Baud setting moved close next to port selection
#endif
#ifdef SerUSB // Defines for normal Serial0 port
#define SerPri Serial.print #define SerPri Serial.print
#define SerPrln Serial.println #define SerPrln Serial.println
#define SerRea Serial.read #define SerRea Serial.read

View File

@ -45,25 +45,41 @@
//#define IsGPS // Do we have a GPS connected //#define IsGPS // Do we have a GPS connected
//#define IsNEWMTEK // Do we have MTEK with new firmware //#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 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 //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 IsAM // Do we have motormount LED's. AM = Atraction Mode
//#define UseAirspeed //#define UseAirspeed
//#define UseBMP //#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 #define CONFIGURATOR
////////////////////
// Telemetry
// Serial data, do we have FTDI cable or Xbee on Telemetry port as our primary command link // 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 SerXbee
//#define Ser0 // FTDI/USB Port Either one // Telemetry port speed, default is 115200
//#define Ser3 // Telemetry port #define SerBau 115200
//////////////////////
// Flight orientation
// Frame build condiguration // Frame build condiguration
#define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration #define FLIGHT_MODE_+ // Traditional "one arm as nose" frame configuration
//#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms //#define FLIGHT_MODE_X // Frame orientation 45 deg to CCW, nose between two arms
/* ************************************************************ */ /* ************************************************************ */
/* **************** MAIN PROGRAM - INCLUDES ******************* */ /* **************** MAIN PROGRAM - INCLUDES ******************* */
/* ************************************************************ */ /* ************************************************************ */
@ -92,6 +108,7 @@
/* Software version */ /* Software version */
#define VER 1.5 // Current software version (only numeric values) #define VER 1.5 // Current software version (only numeric values)
/* ************************************************************ */ /* ************************************************************ */
/* ************* MAIN PROGRAM - DECLARATIONS ****************** */ /* ************* MAIN PROGRAM - DECLARATIONS ****************** */
/* ************************************************************ */ /* ************************************************************ */
@ -221,50 +238,72 @@ void loop()
case 0: // Magnetometer reading (10Hz) case 0: // Magnetometer reading (10Hz)
medium_loopCounter++; medium_loopCounter++;
slowLoop++; slowLoop++;
#ifdef IsMAG #ifdef IsMAG
if (MAGNETOMETER == 1) { if (MAGNETOMETER == 1) {
APM_Compass.Read(); // Read magnetometer APM_Compass.Read(); // Read magnetometer
APM_Compass.Calculate(roll,pitch); // Calculate heading APM_Compass.Calculate(roll,pitch); // Calculate heading
} }
#endif #endif
break; break;
case 1: // Barometer reading (2x10Hz = 20Hz) case 1: // Barometer reading (2x10Hz = 20Hz)
medium_loopCounter++; medium_loopCounter++;
#ifdef UseBMP #ifdef UseBMP
if (APM_BMP085.Read()){ if (APM_BMP085.Read()){
read_baro(); read_baro();
Baro_new_data = 1; Baro_new_data = 1;
} }
#endif #endif
break; break;
case 2: // Send serial telemetry (10Hz) case 2: // Send serial telemetry (10Hz)
medium_loopCounter++; medium_loopCounter++;
#ifdef CONFIGURATOR #ifdef CONFIGURATOR
sendSerialTelemetry(); sendSerialTelemetry();
#endif #endif
break; break;
case 3: // Read serial telemetry (10Hz) case 3: // Read serial telemetry (10Hz)
medium_loopCounter++; medium_loopCounter++;
#ifdef CONFIGURATOR #ifdef CONFIGURATOR
readSerialCommand(); readSerialCommand();
#endif #endif
break; break;
case 4: // second Barometer reading (2x10Hz = 20Hz) case 4: // second Barometer reading (2x10Hz = 20Hz)
medium_loopCounter++; medium_loopCounter++;
#ifdef UseBMP #ifdef UseBMP
if (APM_BMP085.Read()){ if (APM_BMP085.Read()){
read_baro(); read_baro();
Baro_new_data = 1; Baro_new_data = 1;
} }
#endif #endif
break; break;
case 5: // Battery monitor (10Hz) case 5: // Battery monitor (10Hz)
medium_loopCounter=0; medium_loopCounter=0;
#if BATTERY_EVENT == 1 #if BATTERY_EVENT == 1
read_battery(); // Battery monitor read_battery(); // Battery monitor
#endif #endif
break; 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;
}
}
} }

View File

@ -23,15 +23,15 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with this program. If not, see <http://www.gnu.org/licenses/>.
* ************************************************************** * * ************************************************************** *
ChangeLog: ChangeLog:
* ************************************************************** * * ************************************************************** *
TODO: TODO:
* ************************************************************** */ * ************************************************************** */
// //
// Function : send_message() // Function : send_message()
// //
@ -61,7 +61,7 @@ void send_message(byte severity, const char *str) // This is the instance of se
void readSerialCommand() { void readSerialCommand() {
// Check for serial message // Check for serial message
if (SerAva()) { if (SerAva()) {
queryType = SerRea();
switch (queryType) { switch (queryType) {
case 'A': // Stable PID case 'A': // Stable PID
KP_QUAD_ROLL = readFloatSerial(); KP_QUAD_ROLL = readFloatSerial();
@ -154,7 +154,7 @@ void sendSerialTelemetry() {
float aux_float[3]; // used for sensor calibration float aux_float[3]; // used for sensor calibration
switch (queryType) { switch (queryType) {
case '=': // Reserved debug command to view any variable from Serial Monitor case '=': // Reserved debug command to view any variable from Serial Monitor
/* SerPri(("throttle ="); /* SerPri(("throttle =");
SerPrln(ch_throttle); SerPrln(ch_throttle);
SerPri("control roll ="); SerPri("control roll =");
SerPrln(control_roll-CHANN_CENTER); SerPrln(control_roll-CHANN_CENTER);
@ -268,7 +268,7 @@ void sendSerialTelemetry() {
queryType = 'X'; queryType = 'X';
break; break;
case 'L': // Spare case 'L': // Spare
// RadioCalibration(); // RadioCalibration();
queryType = 'X'; queryType = 'X';
break; break;
case 'N': // Send magnetometer config case 'N': // Send magnetometer config
@ -351,6 +351,20 @@ void sendSerialTelemetry() {
SerPri(read_adc(3)); SerPri(read_adc(3));
comma(); comma();
SerPrln(read_adc(5)); 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; break;
case 'T': // Spare case 'T': // Spare
break; break;
@ -438,3 +452,4 @@ float readFloatSerial() {
while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128)); while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128));
return atof(data); return atof(data);
} }

View File

@ -85,9 +85,14 @@ void APM_Init() {
DataFlash.StartWrite(1); // Start a write session on page 1 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"); //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) // Check if we enable the DataFlash log Read Mode (switch)
// If we press switch 1 at startup we read the Dataflash eeprom // If we press switch 1 at startup we read the Dataflash eeprom
while (digitalRead(SW1_pin)==0) while (digitalRead(SW1_pin)==0)
@ -126,5 +131,6 @@ void APM_Init() {
digitalWrite(RI_LED, HIGH); digitalWrite(RI_LED, HIGH);
digitalWrite(LE_LED, HIGH); digitalWrite(LE_LED, HIGH);
#endif #endif
} }