Merge branch 'master' of https://code.google.com/p/ardupilot-mega into auto-approach

Conflicts:
	ArduCopter/Parameters.h
This commit is contained in:
Adam M Rivera 2012-04-16 10:23:01 -05:00
commit f9affb3295
11 changed files with 35 additions and 9 deletions

View File

@ -2177,6 +2177,10 @@ static void tuning(){
g.pid_optflow_roll.kD(tuning_value);
g.pid_optflow_pitch.kD(tuning_value);
break;
case CH6_AHRS_YAW_KP:
ahrs._kp_yaw.set(tuning_value);
break;
}
}

View File

@ -100,9 +100,9 @@ public:
k_param_sonar_type,
k_param_super_simple,
k_param_rtl_land_enabled,
k_param_rtl_approach_alt,
k_param_axis_enabled,
k_param_copter_leds_mode, //159
k_param_copter_leds_mode, //158
k_param_ahrs, // AHRS group
//
// 160: Navigation parameters
@ -110,6 +110,7 @@ public:
k_param_RTL_altitude = 160,
k_param_crosstrack_gain,
k_param_auto_land_timeout,
k_param_rtl_approach_alt,
//

View File

@ -136,12 +136,13 @@ static const AP_Param::Info var_info[] PROGMEM = {
GOBJECT(compass, "COMPASS_", Compass),
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
GOBJECT(imu, "IMU_", IMU)
GOBJECT(imu, "IMU_", IMU),
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#if FRAME_CONFIG == HELI_FRAME
,GOBJECT(motors, "H_", AP_MotorsHeli)
GOBJECT(motors, "H_", AP_MotorsHeli),
#else
,GOBJECT(motors, "MOT_", AP_Motors)
GOBJECT(motors, "MOT_", AP_Motors),
#endif
};

View File

@ -185,6 +185,8 @@
#define CH6_LOITER_RATE_KI 28
#define CH6_LOITER_RATE_KD 23
#define CH6_AHRS_YAW_KP 30
// nav byte mask
// -------------

View File

@ -84,6 +84,7 @@ public:
k_param_airspeed_offset,
k_param_sonar_enabled,
k_param_airspeed_enabled,
k_param_ahrs, // AHRS group
//
// 150: Navigation parameters

View File

@ -125,7 +125,8 @@ static const AP_Param::Info var_info[] PROGMEM = {
GOBJECT(compass, "COMPASS_", Compass),
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
GOBJECT(imu, "IMU_", IMU)
GOBJECT(imu, "IMU_", IMU),
GOBJECT(ahrs, "AHRS_", AP_AHRS)
};

View File

@ -5,3 +5,6 @@ list below
----------------
Test Developer ...
Chris Anderson
Phil Cole put this here after rebasing an old branch to master.

View File

@ -82,6 +82,8 @@ public:
// attitude
virtual Matrix3f get_dcm_matrix(void) = 0;
static const struct AP_Param::GroupInfo var_info[];
protected:
// pointer to compass object, if enabled
Compass * _compass;

View File

@ -23,6 +23,12 @@
// from the GPS and wait for the ground speed to get above GPS_SPEED_MIN
#define GPS_SPEED_RESET 100
// table of user settable parameters
const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
AP_GROUPINFO("YAW_P", 0, AP_AHRS_DCM, _kp_yaw),
AP_GROUPEND
};
// run a full DCM update round
void
AP_AHRS_DCM::update(void)
@ -453,7 +459,7 @@ AP_AHRS_DCM::drift_correction(float deltat)
// allow the yaw reference source to affect all 3 components
// of _omega_yaw_P as we need to be able to correctly hold a
// heading when roll and pitch are non-zero
_omega_yaw_P = error * _kp_yaw;
_omega_yaw_P = error * _kp_yaw.get();
// add yaw correction to integrator correction vector, but
// only for the z gyro. We rely on the accelerometers for x

View File

@ -17,7 +17,7 @@ public:
AP_AHRS_DCM(IMU *imu, GPS *&gps) : AP_AHRS(imu, gps)
{
_kp_roll_pitch = 0.13;
_kp_yaw = 0.4;
_kp_yaw.set(0.4);
_dcm_matrix(Vector3f(1, 0, 0),
Vector3f(0, 1, 0),
Vector3f(0, 0, 1));
@ -42,10 +42,12 @@ public:
float get_error_rp(void);
float get_error_yaw(void);
// settable parameters
AP_Float _kp_yaw;
private:
float _kp_roll_pitch;
float _ki_roll_pitch;
float _kp_yaw;
float _ki_yaw;
bool _have_initial_yaw;

View File

@ -32,6 +32,9 @@ public:
float get_error_rp(void) { return 0; }
float get_error_yaw(void) { return 0; }
// settable parameters
AP_Float _kp_yaw;
private:
Vector3f _omega;
};