mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Plane: setup better defaults for tailsitters
This commit is contained in:
parent
fafd940dd5
commit
36d8f730e1
@ -370,10 +370,15 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
static const struct {
|
||||
struct defaults_struct {
|
||||
const char *name;
|
||||
float value;
|
||||
} defaults_table[] = {
|
||||
};
|
||||
|
||||
/*
|
||||
defaults for all quadplanes
|
||||
*/
|
||||
static const struct defaults_struct defaults_table[] = {
|
||||
{ "Q_A_RAT_RLL_P", 0.25 },
|
||||
{ "Q_A_RAT_RLL_I", 0.25 },
|
||||
{ "Q_A_RAT_RLL_FILT", 10.0 },
|
||||
@ -383,6 +388,19 @@ static const struct {
|
||||
{ "Q_M_SPOOL_TIME", 0.25 },
|
||||
};
|
||||
|
||||
/*
|
||||
extra defaults for tailsitters
|
||||
*/
|
||||
static const struct defaults_struct defaults_table_tailsitter[] = {
|
||||
{ "KFF_RDDRMIX", 0.02 },
|
||||
{ "Q_A_RAT_PIT_FF", 0.2 },
|
||||
{ "Q_A_RAT_YAW_FF", 0.2 },
|
||||
{ "Q_A_RAT_YAW_I", 0.18 },
|
||||
{ "LIM_PITCH_MAX", 3000 },
|
||||
{ "LIM_PITCH_MIN", -3000 },
|
||||
{ "MIXING_GAIN", 1.0 },
|
||||
};
|
||||
|
||||
QuadPlane::QuadPlane(AP_AHRS_NavEKF &_ahrs) :
|
||||
ahrs(_ahrs)
|
||||
{
|
||||
@ -567,19 +585,33 @@ failed:
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
setup default parameters from a defaults_struct table
|
||||
*/
|
||||
void QuadPlane::setup_defaults_table(const struct defaults_struct *table, uint8_t count)
|
||||
{
|
||||
for (uint8_t i=0; i<count; i++) {
|
||||
if (!AP_Param::set_default_by_name(table[i].name, table[i].value)) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "QuadPlane setup failure for %s",
|
||||
table[i].name);
|
||||
AP_HAL::panic("quadplane bad default %s", table[i].name);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
setup default parameters from defaults_table
|
||||
*/
|
||||
void QuadPlane::setup_defaults(void)
|
||||
{
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(defaults_table); i++) {
|
||||
if (!AP_Param::set_default_by_name(defaults_table[i].name, defaults_table[i].value)) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "QuadPlane setup failure for %s",
|
||||
defaults_table[i].name);
|
||||
AP_HAL::panic("quadplane bad default %s", defaults_table[i].name);
|
||||
}
|
||||
}
|
||||
setup_defaults_table(defaults_table, ARRAY_SIZE(defaults_table));
|
||||
|
||||
enum AP_Motors::motor_frame_class motor_class;
|
||||
motor_class = (enum AP_Motors::motor_frame_class)frame_class.get();
|
||||
if (motor_class == AP_Motors::MOTOR_FRAME_TAILSITTER) {
|
||||
setup_defaults_table(defaults_table_tailsitter, ARRAY_SIZE(defaults_table_tailsitter));
|
||||
}
|
||||
|
||||
// reset ESC calibration
|
||||
if (esc_calibration != 0) {
|
||||
esc_calibration.set_and_save(0);
|
||||
|
@ -28,7 +28,6 @@ public:
|
||||
void control_auto(const Location &loc);
|
||||
bool init_mode(void);
|
||||
bool setup(void);
|
||||
void setup_defaults(void);
|
||||
|
||||
void vtol_position_controller(void);
|
||||
void setup_target_position(void);
|
||||
@ -196,6 +195,9 @@ private:
|
||||
void check_throttle_suppression(void);
|
||||
|
||||
void run_z_controller(void);
|
||||
|
||||
void setup_defaults(void);
|
||||
void setup_defaults_table(const struct defaults_struct *defaults, uint8_t count);
|
||||
|
||||
AP_Int16 transition_time_ms;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user