mirror of https://github.com/ArduPilot/ardupilot
ACM: TradHeli
Bringing in Low Pass Filter for Rate Controllers
This commit is contained in:
parent
5b4321d367
commit
07d7d90882
|
@ -17,7 +17,7 @@
|
|||
//#define DMP_ENABLED ENABLED
|
||||
//#define SECONDARY_DMP_ENABLED ENABLED // allows running DMP in parallel with DCM for testing purposes
|
||||
|
||||
#define FRAME_CONFIG HELI_FRAME
|
||||
//#define FRAME_CONFIG QUAD_FRAME
|
||||
/*
|
||||
* options:
|
||||
* QUAD_FRAME
|
||||
|
|
|
@ -103,6 +103,7 @@
|
|||
#include <ModeFilter.h> // Mode Filter from Filter library
|
||||
#include <AverageFilter.h> // Mode Filter from Filter library
|
||||
#include <AP_LeadFilter.h> // GPS Lead filter
|
||||
#include <LowPassFilter.h> // Low Pass Filter library
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Camera.h> // Photo or video camera
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
|
@ -613,9 +614,9 @@ int32_t pitch_axis;
|
|||
AP_LeadFilter xLeadFilter; // Long GPS lag filter
|
||||
AP_LeadFilter yLeadFilter; // Lat GPS lag filter
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// LowPassFilterFloat rate_roll_filter; // Rate Roll filter
|
||||
// LowPassFilterFloat rate_pitch_filter; // Rate Pitch filter 598 LowPassFilterFloat rate_pitch_filter; // Rate Pitch filter
|
||||
// LowPassFilterFloat rate_yaw_filter; // Rate Yaw filter 599 LowPassFilterFloat rate_yaw_filter; // Rate Yaw filter
|
||||
LowPassFilterFloat rate_roll_filter; // Rate Roll filter
|
||||
LowPassFilterFloat rate_pitch_filter; // Rate Pitch filter 598 LowPassFilterFloat rate_pitch_filter; // Rate Pitch filter
|
||||
LowPassFilterFloat rate_yaw_filter; // Rate Yaw filter 599 LowPassFilterFloat rate_yaw_filter; // Rate Yaw filter
|
||||
#endif // HELI_FRAME
|
||||
|
||||
// Barometer filter
|
||||
|
|
|
@ -259,9 +259,7 @@ update_rate_contoller_targets()
|
|||
}
|
||||
}
|
||||
|
||||
///////////////////////////////////////////////////////////////////////////////////
|
||||
// FILTERS DOES NOT BUILD -- NEEDS UPDATED LOWPASS FILTER LIBRARY
|
||||
/*
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// init_rate_controllers - set-up filters for rate controller inputs
|
||||
void init_rate_controllers()
|
||||
|
@ -274,7 +272,7 @@ void init_rate_controllers()
|
|||
// other option for initialisation is rate_roll_filter.set_cutoff_frequency(<time_step>,<cutoff_freq>);
|
||||
}
|
||||
#endif // HELI_FRAME
|
||||
*/
|
||||
|
||||
|
||||
// run roll, pitch and yaw rate controllers and send output to motors
|
||||
// targets for these controllers comes from stabilize controllers
|
||||
|
@ -308,7 +306,7 @@ get_heli_rate_roll(int32_t target_rate)
|
|||
current_rate = (omega.x * DEGX100);
|
||||
|
||||
// filter input
|
||||
// current_rate = rate_roll_filter.apply(current_rate);
|
||||
current_rate = rate_roll_filter.apply(current_rate);
|
||||
|
||||
// call pid controller
|
||||
rate_error = target_rate - (omega.x * DEGX100);
|
||||
|
@ -361,7 +359,7 @@ get_heli_rate_pitch(int32_t target_rate)
|
|||
current_rate = (omega.y * DEGX100);
|
||||
|
||||
// filter input
|
||||
// current_rate = rate_pitch_filter.apply(current_rate);
|
||||
current_rate = rate_pitch_filter.apply(current_rate);
|
||||
|
||||
// call pid controller
|
||||
rate_error = target_rate - (omega.y * DEGX100);
|
||||
|
|
|
@ -291,7 +291,7 @@ static void init_ardupilot()
|
|||
|
||||
#if FRAME_CONIG == HELI_FRAME
|
||||
// initialise controller filters
|
||||
// init_rate_controllers();
|
||||
init_rate_controllers();
|
||||
#endif // HELI_FRAME
|
||||
|
||||
// initialize commands
|
||||
|
|
Loading…
Reference in New Issue