2.0.12 Very small Yaw Iterm added. reverted to earlier Loiter limit.
Slight tweak to Alt hold. git-svn-id: https://arducopter.googlecode.com/svn/trunk@2397 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
4a1772b5ff
commit
2a53e35ac7
@ -763,7 +763,7 @@ void slow_loop()
|
|||||||
slow_loopCounter++;
|
slow_loopCounter++;
|
||||||
superslow_loopCounter++;
|
superslow_loopCounter++;
|
||||||
|
|
||||||
if(superslow_loopCounter > 1400){ // every 7 minutes
|
if(superslow_loopCounter > 800){ // every 4 minutes
|
||||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||||
if(g.rc_3.control_in == 0 && g.compass_enabled){
|
if(g.rc_3.control_in == 0 && g.compass_enabled){
|
||||||
compass.save_offsets();
|
compass.save_offsets();
|
||||||
|
@ -61,6 +61,7 @@
|
|||||||
# define SONAR_PIN AP_RANGEFINDER_PITOT_TUBE
|
# define SONAR_PIN AP_RANGEFINDER_PITOT_TUBE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// AIRSPEED_SENSOR
|
// AIRSPEED_SENSOR
|
||||||
// AIRSPEED_RATIO
|
// AIRSPEED_RATIO
|
||||||
@ -72,6 +73,7 @@
|
|||||||
# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution
|
# define AIRSPEED_RATIO 1.9936 // Note - this varies from the value in ArduPilot due to the difference in ADC resolution
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// HIL_PROTOCOL OPTIONAL
|
// HIL_PROTOCOL OPTIONAL
|
||||||
// HIL_MODE OPTIONAL
|
// HIL_MODE OPTIONAL
|
||||||
@ -114,6 +116,7 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// GPS_PROTOCOL
|
// GPS_PROTOCOL
|
||||||
//
|
//
|
||||||
@ -124,6 +127,7 @@
|
|||||||
# define GPS_PROTOCOL GPS_PROTOCOL_AUTO
|
# define GPS_PROTOCOL GPS_PROTOCOL_AUTO
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// GCS_PROTOCOL
|
// GCS_PROTOCOL
|
||||||
// GCS_PORT
|
// GCS_PORT
|
||||||
@ -141,6 +145,7 @@
|
|||||||
# define MAV_SYSTEM_ID 1
|
# define MAV_SYSTEM_ID 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Serial port speeds.
|
// Serial port speeds.
|
||||||
//
|
//
|
||||||
@ -175,6 +180,7 @@
|
|||||||
# define HIGH_DISCHARGE 1760
|
# define HIGH_DISCHARGE 1760
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// INPUT_VOLTAGE
|
// INPUT_VOLTAGE
|
||||||
//
|
//
|
||||||
@ -182,6 +188,7 @@
|
|||||||
# define INPUT_VOLTAGE 5.0
|
# define INPUT_VOLTAGE 5.0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// MAGNETOMETER
|
// MAGNETOMETER
|
||||||
#ifndef MAGNETOMETER
|
#ifndef MAGNETOMETER
|
||||||
@ -350,13 +357,13 @@
|
|||||||
# define YAW_P 0.4 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
# define YAW_P 0.4 // increase for more aggressive Yaw Hold, decrease if it's bouncy
|
||||||
#endif
|
#endif
|
||||||
#ifndef YAW_I
|
#ifndef YAW_I
|
||||||
# define YAW_I 0.000 // set to .0001 to try and get over user's steady state error caused by poor balance
|
# define YAW_I 0.0001 // set to .0001 to try and get over user's steady state error caused by poor balance
|
||||||
#endif
|
#endif
|
||||||
#ifndef YAW_D
|
#ifndef YAW_D
|
||||||
# define YAW_D 0.05 // Trying a lower value to prevent odd behavior
|
# define YAW_D 0.05 // Trying a lower value to prevent odd behavior
|
||||||
#endif
|
#endif
|
||||||
#ifndef YAW_IMAX
|
#ifndef YAW_IMAX
|
||||||
# define YAW_IMAX 1 // degrees * 100
|
# define YAW_IMAX .5 // degrees * 100
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
@ -375,7 +382,7 @@
|
|||||||
# define NAV_LOITER_P 2.5 // upped to be a bit more aggressive
|
# define NAV_LOITER_P 2.5 // upped to be a bit more aggressive
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_LOITER_I
|
#ifndef NAV_LOITER_I
|
||||||
# define NAV_LOITER_I 0.05 // upped a bit to deal with wind faster
|
# define NAV_LOITER_I 0.10 // upped a bit to deal with wind faster
|
||||||
#endif
|
#endif
|
||||||
#ifndef NAV_LOITER_D
|
#ifndef NAV_LOITER_D
|
||||||
# define NAV_LOITER_D 0.00
|
# define NAV_LOITER_D 0.00
|
||||||
@ -412,14 +419,15 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Throttle control gains
|
// Throttle control gains
|
||||||
//
|
//
|
||||||
#ifndef THROTTLE_BARO_P
|
#ifndef THROTTLE_BARO_P
|
||||||
# define THROTTLE_BARO_P 0.3
|
# define THROTTLE_BARO_P 0.25
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_BARO_I
|
#ifndef THROTTLE_BARO_I
|
||||||
# define THROTTLE_BARO_I 0.005
|
# define THROTTLE_BARO_I 0.0045
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_BARO_D
|
#ifndef THROTTLE_BARO_D
|
||||||
# define THROTTLE_BARO_D 0.03
|
# define THROTTLE_BARO_D 0.03
|
||||||
@ -472,6 +480,7 @@
|
|||||||
# define CHANNEL_6_TUNING CH6_NONE
|
# define CHANNEL_6_TUNING CH6_NONE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Dataflash logging control
|
// Dataflash logging control
|
||||||
//
|
//
|
||||||
|
@ -37,7 +37,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.11 Beta", main_menu_commands);
|
MENU(main_menu, "AC 2.0.12 Beta", main_menu_commands);
|
||||||
|
|
||||||
void init_ardupilot()
|
void init_ardupilot()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user