mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-23 06:36:45 +08:00
Merge pull request #171 from PX4/fault_detection
Attitude / position estimation and controller improvements
This commit is contained in:
@@ -1850,15 +1850,16 @@ int commander_thread_main(int argc, char *argv[])
|
||||
update_state_machine_mode_manual(stat_pub, ¤t_status, mavlink_fd);
|
||||
|
||||
} else if (sp_man.manual_override_switch < -STICK_ON_OFF_LIMIT) {
|
||||
/* check auto mode switch for correct mode */
|
||||
if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) {
|
||||
/* enable guided mode */
|
||||
update_state_machine_mode_guided(stat_pub, ¤t_status, mavlink_fd);
|
||||
// /* check auto mode switch for correct mode */
|
||||
// if (sp_man.auto_mode_switch > STICK_ON_OFF_LIMIT) {
|
||||
// /* enable guided mode */
|
||||
// update_state_machine_mode_guided(stat_pub, ¤t_status, mavlink_fd);
|
||||
|
||||
} else if (sp_man.auto_mode_switch < -STICK_ON_OFF_LIMIT) {
|
||||
// } else if (sp_man.auto_mode_switch < -STICK_ON_OFF_LIMIT) {
|
||||
// XXX hardcode to auto for now
|
||||
update_state_machine_mode_auto(stat_pub, ¤t_status, mavlink_fd);
|
||||
|
||||
}
|
||||
// }
|
||||
|
||||
} else {
|
||||
/* center stick position, set SAS for all vehicle types */
|
||||
|
||||
@@ -14,50 +14,50 @@ PARAM_DEFINE_FLOAT(FWB_R_LP, 300.0f); // yaw rate low pass cut freq
|
||||
PARAM_DEFINE_FLOAT(FWB_R_HP, 1.0f); // yaw rate high pass
|
||||
|
||||
// stabilization mode
|
||||
PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.5f); // roll rate 2 aileron
|
||||
PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.5f); // pitch rate 2 elevator
|
||||
PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.2f); // yaw rate 2 rudder
|
||||
PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.3f); // roll rate 2 aileron
|
||||
PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.1f); // pitch rate 2 elevator
|
||||
PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.1f); // yaw rate 2 rudder
|
||||
|
||||
// psi -> phi -> p
|
||||
PARAM_DEFINE_FLOAT(FWB_PSI2PHI, 0.5f); // heading 2 roll
|
||||
PARAM_DEFINE_FLOAT(FWB_PHI2P, 1.0f); // roll to roll rate
|
||||
PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.5f); // roll limit, 28 deg
|
||||
PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.3f); // roll limit, 28 deg
|
||||
|
||||
// velocity -> theta
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_P, 0.2f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_P, 1.0f); // velocity to pitch angle PID, prop gain
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f); // integral gain
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f); // derivative gain
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f); // derivative low-pass
|
||||
PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f); // integrator wind up guard
|
||||
PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f); // the max commanded pitch angle
|
||||
PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f); // the min commanded pitch angle
|
||||
|
||||
|
||||
// theta -> q
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f); // pitch angle to pitch-rate PID
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_D_LP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_THE2Q_I_MAX, 0.0f);
|
||||
|
||||
// h -> thr
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f);
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f); // altitude to throttle PID
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_I, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_D, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_D_LP, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_H2THR_I_MAX, 0.0f);
|
||||
|
||||
// crosstrack
|
||||
PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // 90 deg
|
||||
PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.002f);
|
||||
PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90 deg
|
||||
PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain
|
||||
|
||||
// speed command
|
||||
PARAM_DEFINE_FLOAT(FWB_V_MIN, 20.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V_CMD, 22.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V_MAX, 24.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_V_MIN, 20.0f); // minimum commanded velocity
|
||||
PARAM_DEFINE_FLOAT(FWB_V_CMD, 22.0f); // commanded velocity
|
||||
PARAM_DEFINE_FLOAT(FWB_V_MAX, 24.0f); // maximum commanded velocity
|
||||
|
||||
// trim
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_AIL, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_ELV, 0.005f);
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_RDR, 0.0f);
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.81f);
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_AIL, 0.0f); // trim aileron, normalized (-1,1)
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_ELV, 0.005f); // trim elevator (-1,1)
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_RDR, 0.0f); // trim rudder (-1,1)
|
||||
PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1)
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -68,52 +68,108 @@
|
||||
class KalmanNav : public control::SuperBlock
|
||||
{
|
||||
public:
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
KalmanNav(SuperBlock *parent, const char *name);
|
||||
|
||||
/**
|
||||
* Deconstuctor
|
||||
*/
|
||||
|
||||
virtual ~KalmanNav() {};
|
||||
/**
|
||||
* The main callback function for the class
|
||||
*/
|
||||
void update();
|
||||
|
||||
|
||||
/**
|
||||
* Publication update
|
||||
*/
|
||||
virtual void updatePublications();
|
||||
void predictFast(float dt);
|
||||
void predictSlow(float dt);
|
||||
void correctAtt();
|
||||
void correctPos();
|
||||
|
||||
/**
|
||||
* State prediction
|
||||
* Continuous, non-linear
|
||||
*/
|
||||
int predictState(float dt);
|
||||
|
||||
/**
|
||||
* State covariance prediction
|
||||
* Continuous, linear
|
||||
*/
|
||||
int predictStateCovariance(float dt);
|
||||
|
||||
/**
|
||||
* Attitude correction
|
||||
*/
|
||||
int correctAtt();
|
||||
|
||||
/**
|
||||
* Position correction
|
||||
*/
|
||||
int correctPos();
|
||||
|
||||
/**
|
||||
* Overloaded update parameters
|
||||
*/
|
||||
virtual void updateParams();
|
||||
protected:
|
||||
math::Matrix F;
|
||||
math::Matrix G;
|
||||
math::Matrix P;
|
||||
math::Matrix V;
|
||||
math::Matrix HAtt;
|
||||
math::Matrix RAtt;
|
||||
math::Matrix HPos;
|
||||
math::Matrix RPos;
|
||||
math::Dcm C_nb;
|
||||
math::Quaternion q;
|
||||
control::UOrbSubscription<sensor_combined_s> _sensors;
|
||||
control::UOrbSubscription<vehicle_gps_position_s> _gps;
|
||||
control::UOrbSubscription<parameter_update_s> _param_update;
|
||||
control::UOrbPublication<vehicle_global_position_s> _pos;
|
||||
control::UOrbPublication<vehicle_attitude_s> _att;
|
||||
uint64_t _pubTimeStamp;
|
||||
uint64_t _fastTimeStamp;
|
||||
uint64_t _slowTimeStamp;
|
||||
uint64_t _attTimeStamp;
|
||||
uint64_t _outTimeStamp;
|
||||
uint16_t _navFrames;
|
||||
uint16_t _missFast;
|
||||
uint16_t _missSlow;
|
||||
float fN, fE, fD;
|
||||
// kalman filter
|
||||
math::Matrix F; /**< Jacobian(f,x), where dx/dt = f(x,u) */
|
||||
math::Matrix G; /**< noise shaping matrix for gyro/accel */
|
||||
math::Matrix P; /**< state covariance matrix */
|
||||
math::Matrix P0; /**< initial state covariance matrix */
|
||||
math::Matrix V; /**< gyro/ accel noise matrix */
|
||||
math::Matrix HAtt; /**< attitude measurement matrix */
|
||||
math::Matrix RAtt; /**< attitude measurement noise matrix */
|
||||
math::Matrix HPos; /**< position measurement jacobian matrix */
|
||||
math::Matrix RPos; /**< position measurement noise matrix */
|
||||
// attitude
|
||||
math::Dcm C_nb; /**< direction cosine matrix from body to nav frame */
|
||||
math::Quaternion q; /**< quaternion from body to nav frame */
|
||||
// subscriptions
|
||||
control::UOrbSubscription<sensor_combined_s> _sensors; /**< sensors sub. */
|
||||
control::UOrbSubscription<vehicle_gps_position_s> _gps; /**< gps sub. */
|
||||
control::UOrbSubscription<parameter_update_s> _param_update; /**< parameter update sub. */
|
||||
// publications
|
||||
control::UOrbPublication<vehicle_global_position_s> _pos; /**< position pub. */
|
||||
control::UOrbPublication<vehicle_attitude_s> _att; /**< attitude pub. */
|
||||
// time stamps
|
||||
uint64_t _pubTimeStamp; /**< output data publication time stamp */
|
||||
uint64_t _predictTimeStamp; /**< prediction time stamp */
|
||||
uint64_t _attTimeStamp; /**< attitude correction time stamp */
|
||||
uint64_t _outTimeStamp; /**< output time stamp */
|
||||
// frame count
|
||||
uint16_t _navFrames; /**< navigation frames completed in output cycle */
|
||||
// miss counts
|
||||
uint16_t _miss; /**< number of times fast prediction loop missed */
|
||||
// accelerations
|
||||
float fN, fE, fD; /**< navigation frame acceleration */
|
||||
// states
|
||||
enum {PHI = 0, THETA, PSI, VN, VE, VD, LAT, LON, ALT};
|
||||
float phi, theta, psi;
|
||||
float vN, vE, vD;
|
||||
double lat, lon, alt;
|
||||
control::BlockParam<float> _vGyro;
|
||||
control::BlockParam<float> _vAccel;
|
||||
control::BlockParam<float> _rMag;
|
||||
control::BlockParam<float> _rGpsVel;
|
||||
control::BlockParam<float> _rGpsPos;
|
||||
control::BlockParam<float> _rGpsAlt;
|
||||
control::BlockParam<float> _rAccel;
|
||||
enum {PHI = 0, THETA, PSI, VN, VE, VD, LAT, LON, ALT}; /**< state enumeration */
|
||||
float phi, theta, psi; /**< 3-2-1 euler angles */
|
||||
float vN, vE, vD; /**< navigation velocity, m/s */
|
||||
double lat, lon, alt; /**< lat, lon, alt, radians */
|
||||
// parameters
|
||||
control::BlockParam<float> _vGyro; /**< gyro process noise */
|
||||
control::BlockParam<float> _vAccel; /**< accelerometer process noise */
|
||||
control::BlockParam<float> _rMag; /**< magnetometer measurement noise */
|
||||
control::BlockParam<float> _rGpsVel; /**< gps velocity measurement noise */
|
||||
control::BlockParam<float> _rGpsPos; /**< gps position measurement noise */
|
||||
control::BlockParam<float> _rGpsAlt; /**< gps altitude measurement noise */
|
||||
control::BlockParam<float> _rAccel; /**< accelerometer measurement noise */
|
||||
control::BlockParam<float> _magDip; /**< magnetic inclination with level */
|
||||
control::BlockParam<float> _magDec; /**< magnetic declination, clockwise rotation */
|
||||
control::BlockParam<float> _g; /**< gravitational constant */
|
||||
control::BlockParam<float> _faultPos; /**< fault detection threshold for position */
|
||||
control::BlockParam<float> _faultAtt; /**< fault detection threshold for attitude */
|
||||
// status
|
||||
bool _attitudeInitialized;
|
||||
bool _positionInitialized;
|
||||
uint16_t _attitudeInitCounter;
|
||||
// accessors
|
||||
int32_t getLatDegE7() { return int32_t(lat * 1.0e7 * M_RAD_TO_DEG); }
|
||||
void setLatDegE7(int32_t val) { lat = val / 1.0e7 / M_RAD_TO_DEG; }
|
||||
int32_t getLonDegE7() { return int32_t(lon * 1.0e7 * M_RAD_TO_DEG); }
|
||||
|
||||
@@ -1,10 +1,16 @@
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
/*PARAM_DEFINE_FLOAT(NAME,0.0f);*/
|
||||
PARAM_DEFINE_FLOAT(KF_V_GYRO, 0.01f);
|
||||
PARAM_DEFINE_FLOAT(KF_V_ACCEL, 0.01f);
|
||||
PARAM_DEFINE_FLOAT(KF_V_GYRO, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_V_ACCEL, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_MAG, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_VEL, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_POS, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_ALT, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_POS, 5.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_GPS_ALT, 5.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_R_ACCEL, 1.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_FAULT_POS, 10.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_FAULT_ATT, 10.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_ENV_G, 9.765f);
|
||||
PARAM_DEFINE_FLOAT(KF_ENV_MAG_DIP, 60.0f);
|
||||
PARAM_DEFINE_FLOAT(KF_ENV_MAG_DEC, 0.0f);
|
||||
|
||||
|
||||
@@ -318,9 +318,11 @@ handle_message(mavlink_message_t *msg)
|
||||
static uint16_t hil_frames = 0;
|
||||
static uint64_t old_timestamp = 0;
|
||||
|
||||
/* sensors general */
|
||||
hil_sensors.timestamp = imu.time_usec;
|
||||
|
||||
/* hil gyro */
|
||||
static const float mrad2rad = 1.0e-3f;
|
||||
hil_sensors.timestamp = timestamp;
|
||||
hil_sensors.gyro_counter = hil_counter;
|
||||
hil_sensors.gyro_raw[0] = imu.xgyro;
|
||||
hil_sensors.gyro_raw[1] = imu.ygyro;
|
||||
@@ -367,8 +369,8 @@ handle_message(mavlink_message_t *msg)
|
||||
hil_frames += 1 ;
|
||||
|
||||
// output
|
||||
if ((timestamp - old_timestamp) > 1000000) {
|
||||
printf("receiving hil imu at %d hz\n", hil_frames);
|
||||
if ((timestamp - old_timestamp) > 10000000) {
|
||||
printf("receiving hil imu at %d hz\n", hil_frames/10);
|
||||
old_timestamp = timestamp;
|
||||
hil_frames = 0;
|
||||
}
|
||||
@@ -412,8 +414,8 @@ handle_message(mavlink_message_t *msg)
|
||||
hil_frames += 1 ;
|
||||
|
||||
// output
|
||||
if ((timestamp - old_timestamp) > 1000000) {
|
||||
printf("receiving hil gps at %d hz\n", hil_frames);
|
||||
if ((timestamp - old_timestamp) > 10000000) {
|
||||
printf("receiving hil gps at %d hz\n", hil_frames/10);
|
||||
old_timestamp = timestamp;
|
||||
hil_frames = 0;
|
||||
}
|
||||
@@ -429,6 +431,9 @@ handle_message(mavlink_message_t *msg)
|
||||
static uint16_t hil_frames = 0;
|
||||
static uint64_t old_timestamp = 0;
|
||||
|
||||
/* sensors general */
|
||||
hil_sensors.timestamp = press.time_usec;
|
||||
|
||||
/* baro */
|
||||
/* TODO, set ground_press/ temp during calib */
|
||||
static const float ground_press = 1013.25f; // mbar
|
||||
@@ -454,8 +459,8 @@ handle_message(mavlink_message_t *msg)
|
||||
hil_frames += 1 ;
|
||||
|
||||
// output
|
||||
if ((timestamp - old_timestamp) > 1000000) {
|
||||
printf("receiving hil pressure at %d hz\n", hil_frames);
|
||||
if ((timestamp - old_timestamp) > 10000000) {
|
||||
printf("receiving hil pressure at %d hz\n", hil_frames/10);
|
||||
old_timestamp = timestamp;
|
||||
hil_frames = 0;
|
||||
}
|
||||
|
||||
@@ -718,7 +718,7 @@ uorb_receive_start(void)
|
||||
|
||||
/* --- GLOBAL POS VALUE --- */
|
||||
mavlink_subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
orb_set_interval(mavlink_subs.global_pos_sub, 1000); /* 1Hz active updates */
|
||||
orb_set_interval(mavlink_subs.global_pos_sub, 100); /* 10 Hz active updates */
|
||||
|
||||
/* --- LOCAL POS VALUE --- */
|
||||
mavlink_subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
|
||||
|
||||
Reference in New Issue
Block a user