Updates for 2.0.21

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2459 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-01 05:50:17 +00:00
parent e4cd549599
commit 142f5a5f49
11 changed files with 160 additions and 64 deletions

View File

@ -6,9 +6,10 @@
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#define NAV_TEST 1 // 0 = traditional, 1 = rate controlled
#define YAW_OPTION 0 // 0 = hybrid rate approach, 1 = offset Yaw approach
#define NAV_TEST 1 // 0 = traditional, 1 = rate controlled
#define YAW_OPTION 0 // 0 = hybrid rate approach, 1 = offset Yaw approach
#define AUTO_RESET_LOITER 1 // enables Loiter to reset it's current location based on stick input.
#define CUT_MOTORS 1 // do we cut the motors with no throttle?
// do we want to have camera stabilization?
#define CAMERA_STABILIZER ENABLED

View File

@ -779,6 +779,17 @@ void slow_loop()
read_battery();
#endif
#if AUTO_RESET_LOITER == 1
if(control_mode == LOITER){
if((abs(g.rc_2.control_in) + abs(g.rc_1.control_in)) > 500){
// reset LOITER to current position
long temp = next_WP.alt;
next_WP = current_loc;
next_WP.alt = temp;
}
}
#endif
break;
case 2:
@ -850,6 +861,7 @@ void super_slow_loop()
gcs_simple.ack();
*/
//}
}
void update_GPS(void)
@ -1100,15 +1112,6 @@ void update_current_flight_mode(void)
// allow interactive changing of atitude
adjust_altitude();
#if AUTO_RESET_LOITER == 1
if((g.rc_2.control_in + g.rc_1.control_in) != 0){
// reset LOITER to current position
long temp = next_WP.alt;
next_WP = current_loc;
next_WP.alt = temp;
}
#endif
// Output Pitch, Roll, Yaw and Throttle
// ------------------------------------

View File

@ -27,14 +27,6 @@
/// change in your local copy of APM_Config.h.
///
#include "APM_Config.h" // <== THIS INCLUDE, DO NOT EDIT IT. EVER.
///
/// DO NOT EDIT THIS INCLUDE - if you want to make a local change, make that
/// change in your local copy of APM_Config.h.
///
// Just so that it's completely clear...
#define ENABLED 1
#define DISABLED 0
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
@ -256,7 +248,7 @@
// GROUND_START_DELAY
//
#ifndef GROUND_START_DELAY
# define GROUND_START_DELAY 0
# define GROUND_START_DELAY 3
#endif
@ -567,6 +559,19 @@
#endif
#ifndef NAV_TEST
# define NAV_TEST 1 // 0 = traditional, 1 = rate controlled
#endif
#ifndef YAW_OPTION
# define YAW_OPTION 0 // 0 = hybrid rate approach, 1 = offset Yaw approach
#endif
#ifndef AUTO_RESET_LOITER
# define AUTO_RESET_LOITER 1 // enables Loiter to reset it's current location based on stick input.
#endif
#ifndef CUT_MOTORS
# define CUT_MOTORS 1 // do we cut the motors with no throttle?
#endif
//////////////////////////////////////////////////////////////////////////////
// RC override
//

View File

@ -1,5 +1,8 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// Just so that it's completely clear...
#define ENABLED 1
#define DISABLED 0
// active altitude sensor
// ----------------------

View File

@ -64,6 +64,9 @@ void output_motors_armed()
motor_out[CH_7] = max(motor_out[CH_7], out_min);
motor_out[CH_8] = max(motor_out[CH_8], out_min);
#if CUT_MOTORS == ENABLED
// Send commands to motors
if(g.rc_3.servo_out > 0){
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
@ -85,6 +88,21 @@ void output_motors_armed()
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
}
#else
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
APM_RC.OutputCh(CH_7, motor_out[CH_7]);
APM_RC.OutputCh(CH_8, motor_out[CH_8]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out6_Out7();
APM_RC.Force_Out2_Out3();
#endif
}
void output_motors_disarmed()
@ -198,4 +216,5 @@ void output_motor_test()
delay(1000);
}
*/
#endif

View File

@ -33,7 +33,7 @@ void output_motors_armed()
//Right side
motor_out[CH_3] = g.rc_3.radio_out - g.rc_1.pwm_out - pitch_out; // CW RIGHT BACK
motor_out[CH_2] = g.rc_3.radio_out - g.rc_1.pwm_out + pitch_out; // CCW RIGHT FRONT
//Back side
motor_out[CH_7] = g.rc_3.radio_out - g.rc_2.pwm_out + roll_out; // CW BACK LEFT
motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out - roll_out; // CCW BACK RIGHT
@ -52,13 +52,13 @@ void output_motors_armed()
//Right side
motor_out[CH_3] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW RIGHT
//Back side
motor_out[CH_7] = g.rc_3.radio_out - g.rc_2.pwm_out; // CW BACK
motor_out[CH_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW BACK RIGHT
motor_out[CH_8] = g.rc_3.radio_out + roll_out - pitch_out; // CCW BACK LEFT
}
// Yaw
motor_out[CH_2] += g.rc_4.pwm_out; // CCW
motor_out[CH_4] += g.rc_4.pwm_out; // CCW
@ -80,8 +80,33 @@ void output_motors_armed()
motor_out[CH_10] = max(motor_out[CH_10], out_min);
motor_out[CH_11] = max(motor_out[CH_11], out_min);
// Send commands to motors
if(g.rc_3.servo_out > 0){
#if CUT_MOTORS == ENABLED
// Send commands to motors
if(g.rc_3.servo_out > 0){
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
APM_RC.OutputCh(CH_7, motor_out[CH_7]);
APM_RC.OutputCh(CH_8, motor_out[CH_8]);
APM_RC.OutputCh(CH_10, motor_out[CH_10]);
APM_RC.OutputCh(CH_11, motor_out[CH_11]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out6_Out7();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, 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_4, g.rc_3.radio_min);
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
}
#else
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]);
@ -95,16 +120,7 @@ void output_motors_armed()
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out6_Out7();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, 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_4, g.rc_3.radio_min);
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
APM_RC.OutputCh(CH_10, g.rc_3.radio_min);
APM_RC.OutputCh(CH_11, g.rc_3.radio_min);
}
#endif
}
void output_motors_disarmed()
@ -166,4 +182,5 @@ void output_motor_test()
delay(1000);
}
#endif
#endif

View File

@ -57,8 +57,23 @@ void output_motors_armed()
motor_out[CH_3] = max(motor_out[CH_3], out_min);
motor_out[CH_4] = max(motor_out[CH_4], out_min);
// Send commands to motors
if(g.rc_3.servo_out > 0){
#if CUT_MOTORS == ENABLED
// Send commands to motors
if(g.rc_3.servo_out > 0){
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, 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_4, g.rc_3.radio_min);
}
#else
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]);
@ -66,12 +81,7 @@ void output_motors_armed()
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, 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_4, g.rc_3.radio_min);
}
#endif
}
void output_motors_disarmed()

View File

@ -33,19 +33,33 @@ void output_motors_armed()
motor_out[CH_2] = max(motor_out[CH_2], out_min);
motor_out[CH_4] = max(motor_out[CH_4], out_min);
// Send commands to motors
if(g.rc_3.servo_out > 0){
#if CUT_MOTORS == ENABLED
// Send commands to motors
if(g.rc_3.servo_out > 0){
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
}
#else
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, g.rc_3.radio_min);
APM_RC.OutputCh(CH_2, g.rc_3.radio_min);
APM_RC.OutputCh(CH_4, g.rc_3.radio_min);
}
#endif
}
void output_motors_disarmed()

View File

@ -41,8 +41,29 @@ void output_motors_armed()
motor_out[CH_1] -= g.rc_4.pwm_out; // CW
motor_out[CH_4] -= g.rc_4.pwm_out; // CW
// Send commands to motors
if(g.rc_3.servo_out > 0){
#if CUT_MOTORS == ENABLED
// Send commands to motors
if(g.rc_3.servo_out > 0){
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]);
APM_RC.OutputCh(CH_4, motor_out[CH_4]);
APM_RC.OutputCh(CH_7, motor_out[CH_7]);
APM_RC.OutputCh(CH_8, motor_out[CH_8]);
// InstantPWM
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out6_Out7();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, 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_4, g.rc_3.radio_min);
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
}
#else
APM_RC.OutputCh(CH_1, motor_out[CH_1]);
APM_RC.OutputCh(CH_2, motor_out[CH_2]);
APM_RC.OutputCh(CH_3, motor_out[CH_3]);
@ -54,14 +75,7 @@ void output_motors_armed()
APM_RC.Force_Out0_Out1();
APM_RC.Force_Out6_Out7();
APM_RC.Force_Out2_Out3();
}else{
APM_RC.OutputCh(CH_1, 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_4, g.rc_3.radio_min);
APM_RC.OutputCh(CH_7, g.rc_3.radio_min);
APM_RC.OutputCh(CH_8, g.rc_3.radio_min);
}
#endif
}
void output_motors_disarmed()

View File

@ -358,6 +358,7 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
init_compass();
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
clear_offsets();
g.compass_enabled.set_and_save(false);
}else{
@ -404,14 +405,20 @@ setup_sonar(uint8_t argc, const Menu::arg *argv)
return 0;
}
void clear_offsets()
{
Vector3f _offsets;
compass.set_offsets(_offsets);
compass.save_offsets();
}
static int8_t
setup_mag_offset(uint8_t argc, const Menu::arg *argv)
{
Vector3f _offsets;
if (!strcmp_P(argv[1].str, PSTR("c"))) {
compass.set_offsets(_offsets);
compass.save_offsets();
clear_offsets();
report_compass();
return (0);
}

View File

@ -37,7 +37,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = {
};
// Create the top-level menu object.
MENU(main_menu, "AC 2.0.20 Beta", main_menu_commands);
MENU(main_menu, "AC 2.0.21 Beta", main_menu_commands);
void init_ardupilot()
{
@ -259,6 +259,9 @@ void startup_ground(void)
{
gcs.send_text_P(SEVERITY_LOW,PSTR("GROUND START"));
// make Motor light go dark
digitalWrite(A_LED_PIN, LOW);
#if(GROUND_START_DELAY > 0)
//gcs.send_text_P(SEVERITY_LOW, PSTR(" With Delay"));
delay(GROUND_START_DELAY * 1000);