Fixed GCS updates, 
Clear GCS Streamrates by default.
moved fast PWM functions to run all the time (for quads, experiment)
cleaned up Mavlink a bit.




git-svn-id: https://arducopter.googlecode.com/svn/trunk@2678 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-26 06:38:11 +00:00
parent ebfb132f34
commit 4f75842cbc
4 changed files with 465 additions and 510 deletions

View File

@ -528,10 +528,17 @@ void loop()
if (millis() - fiftyhz_loopTimer > 19) { if (millis() - fiftyhz_loopTimer > 19) {
delta_ms_fiftyhz = millis() - fiftyhz_loopTimer; delta_ms_fiftyhz = millis() - fiftyhz_loopTimer;
fiftyhz_loopTimer = millis(); fiftyhz_loopTimer = millis();
//PORTK |= B01000000;
// reads all of the necessary trig functions for cameras, throttle, etc.
update_trig();
medium_loop(); medium_loop();
// Stuff to run at full 50hz, but after the loops
fifty_hz_loop(); fifty_hz_loop();
counter_one_herz++; counter_one_herz++;
if(counter_one_herz == 50){ if(counter_one_herz == 50){
@ -550,10 +557,13 @@ void loop()
resetPerfData(); resetPerfData();
} }
} }
//PORTK &= B10111111;
} }
//PORTK &= B11101111; //PORTK &= B11101111;
} }
// PORTK |= B01000000;
// PORTK &= B10111111;
//
// Main loop // Main loop
void fast_loop() void fast_loop()
{ {
@ -589,10 +599,6 @@ void fast_loop()
void medium_loop() void medium_loop()
{ {
// reads all of the necessary trig functions for cameras, throttle, etc.
update_trig();
// This is the start of the medium (10 Hz) loop pieces // This is the start of the medium (10 Hz) loop pieces
// ----------------------------------------- // -----------------------------------------
switch(medium_loopCounter) { switch(medium_loopCounter) {
@ -690,9 +696,7 @@ void medium_loop()
// perform next command // perform next command
// -------------------- // --------------------
if(control_mode == AUTO){ if(control_mode == AUTO){
//if(home_is_set){ update_commands();
update_commands();
//}
} }
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE
@ -712,9 +716,9 @@ void medium_loop()
gcs.send_message(MSG_ATTITUDE); // Sends attitude data gcs.send_message(MSG_ATTITUDE); // Sends attitude data
#endif #endif
//#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && (HIL_MODE != HIL_MODE_DISABLED || HIL_PORT == 0) #if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && (HIL_MODE != HIL_MODE_DISABLED || HIL_PORT == 0)
// hil.data_stream_send(5,45); hil.data_stream_send(5,45);
//#endif #endif
if (g.log_bitmask & MASK_LOG_MOTORS) if (g.log_bitmask & MASK_LOG_MOTORS)
Log_Write_Motors(); Log_Write_Motors();
@ -826,6 +830,7 @@ void slow_loop()
loop_step = 6; loop_step = 6;
slow_loopCounter++; slow_loopCounter++;
superslow_loopCounter++; superslow_loopCounter++;
Serial.printf("sc: %4.4f \n", imu._sensor_compensation(0,50));
if(superslow_loopCounter > 800){ // every 4 minutes if(superslow_loopCounter > 800){ // every 4 minutes
#if HIL_MODE != HIL_MODE_ATTITUDE #if HIL_MODE != HIL_MODE_ATTITUDE
@ -882,10 +887,9 @@ void slow_loop()
gcs.send_message(MSG_CPU_LOAD, load*100); gcs.send_message(MSG_CPU_LOAD, load*100);
#endif #endif
// XXX This was taking 14ms for no reason!!! #if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && (HIL_MODE != HIL_MODE_DISABLED || HIL_PORT == 0)
//#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && (HIL_MODE != HIL_MODE_DISABLED || HIL_PORT == 0) hil.data_stream_send(1,5);
//hil.data_stream_send(1,5); #endif
//#endif
#if CHANNEL_6_TUNING != CH6_NONE #if CHANNEL_6_TUNING != CH6_NONE
tuning(); tuning();

File diff suppressed because it is too large Load Diff

View File

@ -64,9 +64,6 @@ void output_motors_armed()
APM_RC.OutputCh(CH_2, motor_out[CH_2]); APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]); APM_RC.OutputCh(CH_3, motor_out[CH_3]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]); APM_RC.OutputCh(CH_4, motor_out[CH_4]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
}else{ }else{
APM_RC.OutputCh(CH_1, g.rc_3.radio_min); APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
APM_RC.OutputCh(CH_2, g.rc_3.radio_min); APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
@ -78,10 +75,10 @@ void output_motors_armed()
APM_RC.OutputCh(CH_2, motor_out[CH_2]); APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]); APM_RC.OutputCh(CH_3, motor_out[CH_3]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]); APM_RC.OutputCh(CH_4, motor_out[CH_4]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
#endif #endif
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
} }
void output_motors_disarmed() void output_motors_disarmed()
@ -102,6 +99,10 @@ void output_motors_disarmed()
APM_RC.OutputCh(CH_2, g.rc_3.radio_min); APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
APM_RC.OutputCh(CH_3, g.rc_3.radio_min); APM_RC.OutputCh(CH_3, g.rc_3.radio_min);
APM_RC.OutputCh(CH_4, g.rc_3.radio_min); APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
} }
void output_motor_test() void output_motor_test()

View File

@ -40,7 +40,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
}; };
// Create the top-level menu object. // Create the top-level menu object.
MENU(main_menu, "AC 2.0.26 Beta", main_menu_commands); MENU(main_menu, "AC 2.0.27 Beta", main_menu_commands);
void init_ardupilot() void init_ardupilot()
{ {
@ -100,8 +100,8 @@ void init_ardupilot()
DDRL |= B00000100; // Set Port L, pin 2 to output for the relay DDRL |= B00000100; // Set Port L, pin 2 to output for the relay
// XXX set Analog out 14 to output // XXX set Analog out 14 to output
// 76543210 // 76543210
// DDRK |= B01010000; //DDRK |= B01010000;
#if MOTOR_LEDS == 1 #if MOTOR_LEDS == 1
pinMode(FR_LED, OUTPUT); // GPS status LED pinMode(FR_LED, OUTPUT); // GPS status LED