clean up to work better with the Mission planner and enable Camera control.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2697 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-28 06:31:18 +00:00
parent 0efd0fa1f3
commit 88d258f804
5 changed files with 49 additions and 100 deletions

View File

@ -1,22 +1,10 @@
// Example config file. Use APM_Config.h.reference and the wiki to find additional defines to setup your plane. // Example config file. Take a look at confi.h. Any term define there can be overridden by defining it here.
// Once you upload the code, run the factory "reset" to save all config values to EEPROM.
// After reset, use the setup mode to set your radio limits for CH1-4, and to set your flight modes.
// GPS is auto-selected // GPS is auto-selected
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD //#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
#define NAV_TEST 1 // 0 = traditional, 1 = rate controlled
#define YAW_OPTION 1 // 0 = hybrid rate approach, 1 = offset Yaw approach, 2 = simple hybrid
#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?
#define DYNAMIC_DRIFT 0 // careful!!! 0 = off, 1 = on
// do we want to have camera stabilization?
#define CAMERA_STABILIZER 1
#define BROKEN_SLIDER 0
#define FRAME_CONFIG QUAD_FRAME #define FRAME_CONFIG QUAD_FRAME
/* /*
@ -57,31 +45,8 @@
//#define STABILIZE_PITCH_D 0.11 //#define STABILIZE_PITCH_D 0.11
// Logging
//#define LOG_CURRENT ENABLED
# define LOG_ATTITUDE_FAST DISABLED
# define LOG_ATTITUDE_MED DISABLED
# define LOG_GPS ENABLED
# define LOG_PM ENABLED
# define LOG_CTUN ENABLED
# define LOG_NTUN ENABLED
# define LOG_MODE ENABLED
# define LOG_RAW DISABLED
# define LOG_CMD ENABLED
# define LOG_CURRENT DISABLED
#define MOTOR_LEDS 1 // 0 = off, 1 = on
#define FR_LED AN12 // Mega PE4 pin, OUT7
#define RE_LED AN14 // Mega PE5 pin, OUT6
#define RI_LED AN10 // Mega PH4 pin, OUT5
#define LE_LED AN8 // Mega PH5 pin, OUT4
// experimental!! // experimental!!
// Yaw is controled by targeting home. you will not have Yaw override. // Yaw is controled by targeting home. you will not have Yaw override.
// flying too close to home may induce spins. // flying too close to home may induce spins.
#define SIMPLE_LOOK_AT_HOME 0 #define SIMPLE_LOOK_AT_HOME 0
#define DYNAMIC_DRIFT 0 // careful!!! 0 = off, 1 = on

View File

@ -357,6 +357,10 @@
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// YAW Control // YAW Control
// //
#ifndef YAW_OPTION
# define YAW_OPTION 1 // 0 = hybrid rate approach, 1 = offset Yaw approach
#endif
#if YAW_OPTION == 1 // 0 = hybrid rate approach, 1 = offset Yaw approach #if YAW_OPTION == 1 // 0 = hybrid rate approach, 1 = offset Yaw approach
#ifndef YAW_P #ifndef YAW_P
# define YAW_P 0.6 // increase for more aggressive Yaw Hold, decrease if it's bouncy # define YAW_P 0.6 // increase for more aggressive Yaw Hold, decrease if it's bouncy
@ -409,35 +413,26 @@
# define NAV_LOITER_IMAX 20 // 20° # define NAV_LOITER_IMAX 20 // 20°
#endif #endif
#if NAV_TEST == 1 // 0 = traditional, 1 = rate controlled
#ifndef NAV_WP_P
# define NAV_WP_P 3.0 // for 4.5 ms error = 13.5 pitch #ifndef NAV_WP_P
#endif # define NAV_WP_P 3.0 // for 4.5 ms error = 13.5 pitch
#ifndef NAV_WP_I #endif
# define NAV_WP_I 0.5 // this is a fast ramp up #ifndef NAV_WP_I
#endif # define NAV_WP_I 0.5 // this is a fast ramp up
#ifndef NAV_WP_D #endif
# define NAV_WP_D 0 // slight dampening of a few degrees at most #ifndef NAV_WP_D
#endif # define NAV_WP_D 0 // slight dampening of a few degrees at most
#ifndef NAV_WP_IMAX #endif
# define NAV_WP_IMAX 40 // degrees #ifndef NAV_WP_IMAX
#endif # define NAV_WP_IMAX 40 // degrees
#else
#ifndef NAV_WP_P
# define NAV_WP_P 4.0
#endif
#ifndef NAV_WP_I
# define NAV_WP_I 0.15 //
#endif
#ifndef NAV_WP_D
# define NAV_WP_D 10 // not sure about at all
#endif
#ifndef NAV_WP_IMAX
# define NAV_WP_IMAX 20 // 20 degrees
#endif
#endif #endif
#ifndef WAYPOINT_SPEED
# define WAYPOINT_SPEED 450 // for 4.5 ms error = 13.5 pitch
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Throttle control gains // Throttle control gains
// //
@ -506,7 +501,7 @@
# define LOG_ATTITUDE_FAST DISABLED # define LOG_ATTITUDE_FAST DISABLED
#endif #endif
#ifndef LOG_ATTITUDE_MED #ifndef LOG_ATTITUDE_MED
# define LOG_ATTITUDE_MED ENABLED # define LOG_ATTITUDE_MED DISABLED
#endif #endif
#ifndef LOG_GPS #ifndef LOG_GPS
# define LOG_GPS ENABLED # define LOG_GPS ENABLED
@ -515,10 +510,10 @@
# define LOG_PM ENABLED # define LOG_PM ENABLED
#endif #endif
#ifndef LOG_CTUN #ifndef LOG_CTUN
# define LOG_CTUN DISABLED # define LOG_CTUN ENABLED
#endif #endif
#ifndef LOG_NTUN #ifndef LOG_NTUN
# define LOG_NTUN DISABLED # define LOG_NTUN ENABLED
#endif #endif
#ifndef LOG_MODE #ifndef LOG_MODE
# define LOG_MODE ENABLED # define LOG_MODE ENABLED
@ -585,12 +580,6 @@
#endif #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 #ifndef AUTO_RESET_LOITER
# define AUTO_RESET_LOITER 1 // enables Loiter to reset it's current location based on stick input. # define AUTO_RESET_LOITER 1 // enables Loiter to reset it's current location based on stick input.
#endif #endif
@ -598,6 +587,19 @@
# define CUT_MOTORS 1 // do we cut the motors with no throttle? # define CUT_MOTORS 1 // do we cut the motors with no throttle?
#endif #endif
#ifndef CAMERA_STABILIZER
# define CAMERA_STABILIZER 1 // do we cut the motors with no throttle?
#endif
#ifndef BROKEN_SLIDER
# define BROKEN_SLIDER 0 // 1 = yes (use Yaw to enter CLI mode)
#endif
#ifndef MOTOR_LEDS
# define MOTOR_LEDS 1 // 0 = off, 1 = on
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// RC override // RC override
// //

View File

@ -30,6 +30,12 @@
#define NORMAL_LEDS 0 #define NORMAL_LEDS 0
#define AUTO_TRIM_LEDS 1 #define AUTO_TRIM_LEDS 1
// motor LEDs
#define FR_LED AN12 // Mega PE4 pin, OUT7
#define RE_LED AN14 // Mega PE5 pin, OUT6
#define RI_LED AN10 // Mega PH4 pin, OUT5
#define LE_LED AN8 // Mega PH5 pin, OUT4
// Internal defines, don't edit and expect things to work // Internal defines, don't edit and expect things to work
// ------------------------------------------------------- // -------------------------------------------------------

View File

@ -126,31 +126,6 @@ void calc_nav_output()
nav_pitch = -(float)nav_lat * sin_nav_y; nav_pitch = -(float)nav_lat * sin_nav_y;
} }
#define WAYPOINT_SPEED 450
#if NAV_TEST == 0
void calc_rate_nav()
{
// calc distance error
nav_lat = min((wp_distance * 100), 1800); // +- 20m max error
// Scale response by kP
nav_lat *= g.pid_nav_lat.kP(); // 1800 * 2 = 3600 or 36°
// Scale response by kP
//long output = g.pid_nav_wp.kP() * error;
int dampening = g.pid_nav_wp.kD() * (g_gps->ground_speed - last_ground_speed);
// remember our old speed
last_ground_speed = g_gps->ground_speed;
// dampen our response
nav_lat -= constrain(dampening, -1800, 1800); // +- 20m max error
}
#else
// called after we get GPS read // called after we get GPS read
void calc_rate_nav() void calc_rate_nav()
{ {
@ -177,8 +152,6 @@ void calc_rate_nav()
nav_lat = constrain(nav_lat, -4000, 4000); // +- max error nav_lat = constrain(nav_lat, -4000, 4000); // +- max error
} }
#endif
void calc_bearing_error() void calc_bearing_error()
{ {
bearing_error = nav_bearing - dcm.yaw_sensor; bearing_error = nav_bearing - dcm.yaw_sensor;

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.29 Beta", main_menu_commands); MENU(main_menu, "AC 2.0.30 Beta", main_menu_commands);
void init_ardupilot() void init_ardupilot()
{ {
@ -336,6 +336,9 @@ void startup_ground(void)
SendDebug("\nReady to FLY "); SendDebug("\nReady to FLY ");
//gcs.send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY.")); //gcs.send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
// output control mode to the ground station
gcs.send_message(MSG_HEARTBEAT);
} }
void set_mode(byte mode) void set_mode(byte mode)