mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: added tuning error reporting for quadplanes
This commit is contained in:
parent
26ef71e130
commit
ba3576f027
@ -963,6 +963,10 @@ void QuadPlane::motors_output(void)
|
|||||||
if (motors->armed()) {
|
if (motors->armed()) {
|
||||||
plane.DataFlash.Log_Write_Rate(plane.ahrs, *motors, *attitude_control, *pos_control);
|
plane.DataFlash.Log_Write_Rate(plane.ahrs, *motors, *attitude_control, *pos_control);
|
||||||
Log_Write_QControl_Tuning();
|
Log_Write_QControl_Tuning();
|
||||||
|
uint32_t now = AP_HAL::millis();
|
||||||
|
if (now - last_ctrl_log_ms > 100) {
|
||||||
|
attitude_control->control_monitor_log();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -299,6 +299,9 @@ private:
|
|||||||
uint8_t motor_count; // number of motors to cycle
|
uint8_t motor_count; // number of motors to cycle
|
||||||
} motor_test;
|
} motor_test;
|
||||||
|
|
||||||
|
// time of last control log message
|
||||||
|
uint32_t last_ctrl_log_ms;
|
||||||
|
|
||||||
// tiltrotor control variables
|
// tiltrotor control variables
|
||||||
struct {
|
struct {
|
||||||
AP_Int16 tilt_mask;
|
AP_Int16 tilt_mask;
|
||||||
|
@ -264,3 +264,33 @@ void AP_Tuning_Plane::reload_value(uint8_t parm)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return current controller error
|
||||||
|
*/
|
||||||
|
float AP_Tuning_Plane::controller_error(uint8_t parm)
|
||||||
|
{
|
||||||
|
switch(parm) {
|
||||||
|
// special handling of dual-parameters
|
||||||
|
case TUNING_RATE_ROLL_PI:
|
||||||
|
case TUNING_RATE_ROLL_P:
|
||||||
|
case TUNING_RATE_ROLL_I:
|
||||||
|
case TUNING_RATE_ROLL_D:
|
||||||
|
case TUNING_RATE_PITCH_PI:
|
||||||
|
case TUNING_RATE_PITCH_P:
|
||||||
|
case TUNING_RATE_PITCH_I:
|
||||||
|
case TUNING_RATE_PITCH_D:
|
||||||
|
case TUNING_RATE_YAW_PI:
|
||||||
|
case TUNING_RATE_YAW_P:
|
||||||
|
case TUNING_RATE_YAW_I:
|
||||||
|
case TUNING_RATE_YAW_D:
|
||||||
|
if (!plane.quadplane.available()) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return plane.quadplane.attitude_control->control_monitor_rms_output();
|
||||||
|
|
||||||
|
default:
|
||||||
|
// no special handler
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -83,10 +83,11 @@ private:
|
|||||||
TUNING_SET_AZ = 7,
|
TUNING_SET_AZ = 7,
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Float *get_param_pointer(uint8_t parm);
|
AP_Float *get_param_pointer(uint8_t parm) override;
|
||||||
void save_value(uint8_t parm);
|
void save_value(uint8_t parm) override;
|
||||||
void reload_value(uint8_t parm);
|
void reload_value(uint8_t parm) override;
|
||||||
void set_value(uint8_t parm, float value);
|
void set_value(uint8_t parm, float value) override;
|
||||||
|
float controller_error(uint8_t parm) override;
|
||||||
|
|
||||||
// tuning set arrays
|
// tuning set arrays
|
||||||
static const uint8_t tuning_set_rate_roll_pitch[];
|
static const uint8_t tuning_set_rate_roll_pitch[];
|
||||||
|
Loading…
Reference in New Issue
Block a user