2019-07-29 04:55:40 -03:00
|
|
|
#include "Copter.h"
|
2024-05-13 13:16:57 -03:00
|
|
|
#include <AP_Math/control.h>
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2024-09-04 00:48:37 -03:00
|
|
|
#if MODE_SYSTEMID_ENABLED
|
2019-07-29 04:55:40 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
* Init and run calls for systemId, flight mode
|
|
|
|
*/
|
|
|
|
|
|
|
|
const AP_Param::GroupInfo ModeSystemId::var_info[] = {
|
|
|
|
|
|
|
|
// @Param: _AXIS
|
|
|
|
// @DisplayName: System identification axis
|
2019-12-02 22:34:19 -04:00
|
|
|
// @Description: Controls which axis are being excited. Set to non-zero to see more parameters
|
2019-07-29 04:55:40 -03:00
|
|
|
// @User: Standard
|
2024-01-28 00:06:20 -04:00
|
|
|
// @Values: 0:None, 1:Input Roll Angle, 2:Input Pitch Angle, 3:Input Yaw Angle, 4:Recovery Roll Angle, 5:Recovery Pitch Angle, 6:Recovery Yaw Angle, 7:Rate Roll, 8:Rate Pitch, 9:Rate Yaw, 10:Mixer Roll, 11:Mixer Pitch, 12:Mixer Yaw, 13:Mixer Thrust, 14:Measured Lateral Position, 15:Measured Longitudinal Position, 16:Measured Lateral Velocity, 17:Measured Longitudinal Velocity, 18:Input Lateral Velocity, 19:Input Longitudinal Velocity
|
2019-12-02 22:34:19 -04:00
|
|
|
AP_GROUPINFO_FLAGS("_AXIS", 1, ModeSystemId, axis, 0, AP_PARAM_FLAG_ENABLE),
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
// @Param: _MAGNITUDE
|
|
|
|
// @DisplayName: System identification Chirp Magnitude
|
2019-07-29 04:55:40 -03:00
|
|
|
// @Description: Magnitude of sweep in deg, deg/s and 0-1 for mixer outputs.
|
|
|
|
// @User: Standard
|
2019-10-15 02:38:24 -03:00
|
|
|
AP_GROUPINFO("_MAGNITUDE", 2, ModeSystemId, waveform_magnitude, 15),
|
2019-07-29 04:55:40 -03:00
|
|
|
|
|
|
|
// @Param: _F_START_HZ
|
2019-10-15 02:38:24 -03:00
|
|
|
// @DisplayName: System identification Start Frequency
|
2019-07-29 04:55:40 -03:00
|
|
|
// @Description: Frequency at the start of the sweep
|
|
|
|
// @Range: 0.01 100
|
|
|
|
// @Units: Hz
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("_F_START_HZ", 3, ModeSystemId, frequency_start, 0.5f),
|
|
|
|
|
|
|
|
// @Param: _F_STOP_HZ
|
2019-10-15 02:38:24 -03:00
|
|
|
// @DisplayName: System identification Stop Frequency
|
2019-07-29 04:55:40 -03:00
|
|
|
// @Description: Frequency at the end of the sweep
|
|
|
|
// @Range: 0.01 100
|
|
|
|
// @Units: Hz
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("_F_STOP_HZ", 4, ModeSystemId, frequency_stop, 40),
|
|
|
|
|
|
|
|
// @Param: _T_FADE_IN
|
2019-10-15 02:38:24 -03:00
|
|
|
// @DisplayName: System identification Fade in time
|
2019-07-29 04:55:40 -03:00
|
|
|
// @Description: Time to reach maximum amplitude of sweep
|
|
|
|
// @Range: 0 20
|
|
|
|
// @Units: s
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("_T_FADE_IN", 5, ModeSystemId, time_fade_in, 15),
|
|
|
|
|
|
|
|
// @Param: _T_REC
|
2019-10-15 02:38:24 -03:00
|
|
|
// @DisplayName: System identification Total Sweep length
|
2019-07-29 04:55:40 -03:00
|
|
|
// @Description: Time taken to complete the sweep
|
|
|
|
// @Range: 0 255
|
|
|
|
// @Units: s
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("_T_REC", 6, ModeSystemId, time_record, 70),
|
|
|
|
|
|
|
|
// @Param: _T_FADE_OUT
|
2019-10-15 02:38:24 -03:00
|
|
|
// @DisplayName: System identification Fade out time
|
2019-07-29 04:55:40 -03:00
|
|
|
// @Description: Time to reach zero amplitude at the end of the sweep
|
|
|
|
// @Range: 0 5
|
|
|
|
// @Units: s
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("_T_FADE_OUT", 7, ModeSystemId, time_fade_out, 2),
|
|
|
|
|
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
ModeSystemId::ModeSystemId(void) : Mode()
|
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
|
|
|
|
2021-03-17 18:51:58 -03:00
|
|
|
#define SYSTEM_ID_DELAY 1.0f // time in seconds waited after system id mode change for frequency sweep injection
|
2019-07-29 04:55:40 -03:00
|
|
|
|
|
|
|
// systemId_init - initialise systemId controller
|
|
|
|
bool ModeSystemId::init(bool ignore_checks)
|
|
|
|
{
|
2019-12-02 22:34:19 -04:00
|
|
|
// check if enabled
|
|
|
|
if (axis == 0) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "No axis selected, SID_AXIS = 0");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2024-02-13 23:26:31 -04:00
|
|
|
// ensure we are flying
|
|
|
|
if (!copter.motors->armed() || !copter.ap.auto_armed || copter.ap.land_complete) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Aircraft must be flying");
|
2019-07-29 04:55:40 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2024-02-13 23:26:31 -04:00
|
|
|
if (!is_poscontrol_axis_type()) {
|
2023-08-18 00:56:25 -03:00
|
|
|
|
2023-11-13 19:33:59 -04:00
|
|
|
// System ID is being done on the attitude control loops
|
2024-02-13 23:26:31 -04:00
|
|
|
|
|
|
|
// Can only switch into System ID Axes 1-13 with a flight mode that has manual throttle
|
2023-11-13 19:33:59 -04:00
|
|
|
if (!copter.flightmode->has_manual_throttle()) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires manual throttle");
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-07-29 04:55:40 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2023-08-18 00:56:25 -03:00
|
|
|
copter.input_manager.set_use_stab_col(true);
|
2019-07-29 04:55:40 -03:00
|
|
|
#endif
|
|
|
|
|
2023-08-18 00:56:25 -03:00
|
|
|
} else {
|
|
|
|
|
2023-11-13 19:33:59 -04:00
|
|
|
// System ID is being done on the position control loops
|
2023-08-18 00:56:25 -03:00
|
|
|
|
2024-02-13 23:26:31 -04:00
|
|
|
// Can only switch into System ID Axes 14-19 from Loiter flight mode
|
2023-11-13 19:33:59 -04:00
|
|
|
if (copter.flightmode->mode_number() != Mode::Number::LOITER) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires switch from Loiter");
|
|
|
|
return false;
|
|
|
|
}
|
2023-08-18 00:56:25 -03:00
|
|
|
|
2023-11-13 19:33:59 -04:00
|
|
|
// set horizontal speed and acceleration limits
|
|
|
|
pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
|
|
|
pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
|
|
|
|
|
|
|
|
// initialise the horizontal position controller
|
|
|
|
if (!pos_control->is_active_xy()) {
|
|
|
|
pos_control->init_xy_controller();
|
2023-08-18 00:56:25 -03:00
|
|
|
}
|
2023-11-13 19:33:59 -04:00
|
|
|
|
|
|
|
// set vertical speed and acceleration limits
|
|
|
|
pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
|
|
|
|
pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
|
2023-08-18 00:56:25 -03:00
|
|
|
|
|
|
|
// initialise the vertical position controller
|
|
|
|
if (!pos_control->is_active_z()) {
|
|
|
|
pos_control->init_z_controller();
|
|
|
|
}
|
2024-02-14 20:01:40 -04:00
|
|
|
Vector3f curr_pos;
|
|
|
|
curr_pos = inertial_nav.get_position_neu_cm();
|
2024-05-13 13:16:57 -03:00
|
|
|
target_pos = curr_pos.xy();
|
2023-08-18 00:56:25 -03:00
|
|
|
}
|
|
|
|
|
2019-07-29 04:55:40 -03:00
|
|
|
att_bf_feedforward = attitude_control->get_bf_feedforward();
|
|
|
|
waveform_time = 0.0f;
|
|
|
|
time_const_freq = 2.0f / frequency_start; // Two full cycles at the starting frequency
|
2019-10-15 02:38:24 -03:00
|
|
|
systemid_state = SystemIDModeState::SYSTEMID_STATE_TESTING;
|
2019-07-29 04:55:40 -03:00
|
|
|
log_subsample = 0;
|
|
|
|
|
2022-03-14 23:53:57 -03:00
|
|
|
chirp_input.init(time_record, frequency_start, frequency_stop, time_fade_in, time_fade_out, time_const_freq);
|
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Starting: axis=%d", (unsigned)axis);
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2023-07-13 21:58:09 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2019-10-15 02:38:24 -03:00
|
|
|
copter.Log_Write_SysID_Setup(axis, waveform_magnitude, frequency_start, frequency_stop, time_fade_in, time_const_freq, time_record, time_fade_out);
|
2023-07-13 21:58:09 -03:00
|
|
|
#endif
|
2019-07-29 04:55:40 -03:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2022-04-06 00:58:38 -03:00
|
|
|
// systemId_exit - clean up systemId controller before exiting
|
|
|
|
void ModeSystemId::exit()
|
|
|
|
{
|
2023-10-11 04:41:54 -03:00
|
|
|
// reset the feedforward enabled parameter to the initialized state
|
2022-04-06 00:58:38 -03:00
|
|
|
attitude_control->bf_feedforward(att_bf_feedforward);
|
|
|
|
}
|
|
|
|
|
2019-07-29 04:55:40 -03:00
|
|
|
// systemId_run - runs the systemId controller
|
|
|
|
// should be called at 100hz or more
|
|
|
|
void ModeSystemId::run()
|
|
|
|
{
|
|
|
|
float target_roll, target_pitch;
|
2023-08-18 00:56:25 -03:00
|
|
|
float target_yaw_rate = 0.0f;
|
|
|
|
float pilot_throttle_scaled = 0.0f;
|
|
|
|
float target_climb_rate = 0.0f;
|
|
|
|
Vector2f input_vel;
|
|
|
|
|
2024-02-13 23:26:31 -04:00
|
|
|
if (!is_poscontrol_axis_type()) {
|
2023-08-18 00:56:25 -03:00
|
|
|
|
|
|
|
// apply simple mode transform to pilot inputs
|
|
|
|
update_simple_mode();
|
|
|
|
|
|
|
|
// convert pilot input to lean angles
|
|
|
|
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
|
|
|
|
|
|
|
|
// get pilot's desired yaw rate
|
|
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
|
|
|
|
|
|
|
|
if (!motors->armed()) {
|
|
|
|
// Motors should be Stopped
|
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
|
|
|
|
// Tradheli doesn't set spool state to ground idle when throttle stick is zero. Ground idle only set when
|
|
|
|
// motor interlock is disabled.
|
|
|
|
} else if (copter.ap.throttle_zero && !copter.is_tradheli()) {
|
|
|
|
// Attempting to Land
|
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
|
|
|
|
} else {
|
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
|
|
|
}
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2023-08-18 00:56:25 -03:00
|
|
|
switch (motors->get_spool_state()) {
|
|
|
|
case AP_Motors::SpoolState::SHUT_DOWN:
|
|
|
|
// Motors Stopped
|
2021-05-24 10:42:19 -03:00
|
|
|
attitude_control->reset_yaw_target_and_rate();
|
2023-08-18 00:56:25 -03:00
|
|
|
attitude_control->reset_rate_controller_I_terms();
|
|
|
|
break;
|
2019-11-03 22:54:47 -04:00
|
|
|
|
2023-08-18 00:56:25 -03:00
|
|
|
case AP_Motors::SpoolState::GROUND_IDLE:
|
|
|
|
// Landed
|
2024-02-13 23:26:31 -04:00
|
|
|
// Tradheli initializes targets when going from disarmed to armed state.
|
2023-08-18 00:56:25 -03:00
|
|
|
// init_targets_on_arming is always set true for multicopter.
|
|
|
|
if (motors->init_targets_on_arming()) {
|
|
|
|
attitude_control->reset_yaw_target_and_rate();
|
|
|
|
attitude_control->reset_rate_controller_I_terms_smoothly();
|
|
|
|
}
|
|
|
|
break;
|
2019-11-03 22:54:47 -04:00
|
|
|
|
2023-08-18 00:56:25 -03:00
|
|
|
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
|
|
|
|
// clear landing flag above zero throttle
|
|
|
|
if (!motors->limit.throttle_lower) {
|
|
|
|
set_land_complete(false);
|
|
|
|
}
|
|
|
|
break;
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2023-08-18 00:56:25 -03:00
|
|
|
case AP_Motors::SpoolState::SPOOLING_UP:
|
|
|
|
case AP_Motors::SpoolState::SPOOLING_DOWN:
|
|
|
|
// do nothing
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// get pilot's desired throttle
|
2019-07-29 04:55:40 -03:00
|
|
|
#if FRAME_CONFIG == HELI_FRAME
|
2023-08-18 00:56:25 -03:00
|
|
|
pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
|
2019-07-29 04:55:40 -03:00
|
|
|
#else
|
2023-08-18 00:56:25 -03:00
|
|
|
pilot_throttle_scaled = get_pilot_desired_throttle();
|
2019-07-29 04:55:40 -03:00
|
|
|
#endif
|
|
|
|
|
2023-08-18 00:56:25 -03:00
|
|
|
}
|
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
if ((systemid_state == SystemIDModeState::SYSTEMID_STATE_TESTING) &&
|
|
|
|
(!is_positive(frequency_start) || !is_positive(frequency_stop) || is_negative(time_fade_in) || !is_positive(time_record) || is_negative(time_fade_out) || (time_record <= time_const_freq))) {
|
|
|
|
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
|
2019-07-29 04:55:40 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Parameter Error");
|
|
|
|
}
|
|
|
|
|
|
|
|
waveform_time += G_Dt;
|
2022-03-14 23:53:57 -03:00
|
|
|
waveform_sample = chirp_input.update(waveform_time - SYSTEM_ID_DELAY, waveform_magnitude);
|
|
|
|
waveform_freq_rads = chirp_input.get_frequency_rads();
|
2023-08-18 00:56:25 -03:00
|
|
|
Vector2f disturb_state;
|
2019-10-15 02:38:24 -03:00
|
|
|
switch (systemid_state) {
|
|
|
|
case SystemIDModeState::SYSTEMID_STATE_STOPPED:
|
2022-04-06 00:58:38 -03:00
|
|
|
attitude_control->bf_feedforward(att_bf_feedforward);
|
2019-07-29 04:55:40 -03:00
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case SystemIDModeState::SYSTEMID_STATE_TESTING:
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
if (copter.ap.land_complete) {
|
|
|
|
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
|
2019-07-29 04:55:40 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: Landed");
|
|
|
|
break;
|
|
|
|
}
|
2021-09-06 06:44:18 -03:00
|
|
|
if (attitude_control->lean_angle_deg()*100 > attitude_control->lean_angle_max_cd()) {
|
2019-10-15 02:38:24 -03:00
|
|
|
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
|
2021-09-06 06:44:18 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: lean=%f max=%f", (double)attitude_control->lean_angle_deg(), (double)attitude_control->lean_angle_max_cd());
|
2019-07-29 04:55:40 -03:00
|
|
|
break;
|
|
|
|
}
|
2019-10-15 02:38:24 -03:00
|
|
|
if (waveform_time > SYSTEM_ID_DELAY + time_fade_in + time_const_freq + time_record + time_fade_out) {
|
|
|
|
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
|
2019-07-29 04:55:40 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Finished");
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
switch ((AxisType)axis.get()) {
|
|
|
|
case AxisType::NONE:
|
|
|
|
systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
|
2019-07-29 04:55:40 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: axis = 0");
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::INPUT_ROLL:
|
2019-07-29 04:55:40 -03:00
|
|
|
target_roll += waveform_sample*100.0f;
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::INPUT_PITCH:
|
2019-07-29 04:55:40 -03:00
|
|
|
target_pitch += waveform_sample*100.0f;
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::INPUT_YAW:
|
2019-07-29 04:55:40 -03:00
|
|
|
target_yaw_rate += waveform_sample*100.0f;
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::RECOVER_ROLL:
|
2019-07-29 04:55:40 -03:00
|
|
|
target_roll += waveform_sample*100.0f;
|
|
|
|
attitude_control->bf_feedforward(false);
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::RECOVER_PITCH:
|
2019-07-29 04:55:40 -03:00
|
|
|
target_pitch += waveform_sample*100.0f;
|
|
|
|
attitude_control->bf_feedforward(false);
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::RECOVER_YAW:
|
2019-07-29 04:55:40 -03:00
|
|
|
target_yaw_rate += waveform_sample*100.0f;
|
|
|
|
attitude_control->bf_feedforward(false);
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::RATE_ROLL:
|
2019-07-29 04:55:40 -03:00
|
|
|
attitude_control->rate_bf_roll_sysid(radians(waveform_sample));
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::RATE_PITCH:
|
2019-07-29 04:55:40 -03:00
|
|
|
attitude_control->rate_bf_pitch_sysid(radians(waveform_sample));
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::RATE_YAW:
|
2019-07-29 04:55:40 -03:00
|
|
|
attitude_control->rate_bf_yaw_sysid(radians(waveform_sample));
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::MIX_ROLL:
|
2019-07-29 04:55:40 -03:00
|
|
|
attitude_control->actuator_roll_sysid(waveform_sample);
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::MIX_PITCH:
|
2019-07-29 04:55:40 -03:00
|
|
|
attitude_control->actuator_pitch_sysid(waveform_sample);
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::MIX_YAW:
|
2019-07-29 04:55:40 -03:00
|
|
|
attitude_control->actuator_yaw_sysid(waveform_sample);
|
|
|
|
break;
|
2019-10-15 02:38:24 -03:00
|
|
|
case AxisType::MIX_THROTTLE:
|
2019-07-29 04:55:40 -03:00
|
|
|
pilot_throttle_scaled += waveform_sample;
|
|
|
|
break;
|
2023-08-18 00:56:25 -03:00
|
|
|
case AxisType::DISTURB_POS_LAT:
|
|
|
|
disturb_state.x = 0.0f;
|
|
|
|
disturb_state.y = waveform_sample * 100.0f;
|
2024-01-29 20:05:34 -04:00
|
|
|
disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
|
2023-08-18 00:56:25 -03:00
|
|
|
pos_control->set_disturb_pos_cm(disturb_state);
|
|
|
|
break;
|
|
|
|
case AxisType::DISTURB_POS_LONG:
|
|
|
|
disturb_state.x = waveform_sample * 100.0f;
|
|
|
|
disturb_state.y = 0.0f;
|
2024-01-29 20:05:34 -04:00
|
|
|
disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
|
2023-08-18 00:56:25 -03:00
|
|
|
pos_control->set_disturb_pos_cm(disturb_state);
|
|
|
|
break;
|
|
|
|
case AxisType::DISTURB_VEL_LAT:
|
|
|
|
disturb_state.x = 0.0f;
|
|
|
|
disturb_state.y = waveform_sample * 100.0f;
|
2024-01-29 20:05:34 -04:00
|
|
|
disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
|
2023-08-18 00:56:25 -03:00
|
|
|
pos_control->set_disturb_vel_cms(disturb_state);
|
|
|
|
break;
|
|
|
|
case AxisType::DISTURB_VEL_LONG:
|
|
|
|
disturb_state.x = waveform_sample * 100.0f;
|
|
|
|
disturb_state.y = 0.0f;
|
2024-01-29 20:05:34 -04:00
|
|
|
disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
|
2023-08-18 00:56:25 -03:00
|
|
|
pos_control->set_disturb_vel_cms(disturb_state);
|
|
|
|
break;
|
2024-05-13 20:31:42 -03:00
|
|
|
case AxisType::INPUT_VEL_LAT:
|
2023-08-18 00:56:25 -03:00
|
|
|
input_vel.x = 0.0f;
|
|
|
|
input_vel.y = waveform_sample * 100.0f;
|
2024-01-29 20:05:34 -04:00
|
|
|
input_vel.rotate(attitude_control->get_att_target_euler_rad().z);
|
2023-08-18 00:56:25 -03:00
|
|
|
break;
|
2024-05-13 20:31:42 -03:00
|
|
|
case AxisType::INPUT_VEL_LONG:
|
2023-08-18 00:56:25 -03:00
|
|
|
input_vel.x = waveform_sample * 100.0f;
|
|
|
|
input_vel.y = 0.0f;
|
2024-01-29 20:05:34 -04:00
|
|
|
input_vel.rotate(attitude_control->get_att_target_euler_rad().z);
|
2023-08-18 00:56:25 -03:00
|
|
|
break;
|
2019-07-29 04:55:40 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2024-02-13 23:26:31 -04:00
|
|
|
if (!is_poscontrol_axis_type()) {
|
2023-08-18 00:56:25 -03:00
|
|
|
|
|
|
|
// call attitude controller
|
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
|
|
|
|
|
|
|
// output pilot's throttle
|
|
|
|
attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt);
|
|
|
|
|
|
|
|
} else {
|
|
|
|
|
|
|
|
// relax loiter target if we might be landed
|
|
|
|
if (copter.ap.land_complete_maybe) {
|
|
|
|
pos_control->soften_for_landing_xy();
|
|
|
|
}
|
|
|
|
|
2023-11-13 19:33:59 -04:00
|
|
|
Vector2f accel;
|
2024-02-14 20:01:40 -04:00
|
|
|
target_pos += input_vel * G_Dt;
|
|
|
|
if (is_positive(G_Dt)) {
|
|
|
|
accel = (input_vel - input_vel_last) / G_Dt;
|
|
|
|
input_vel_last = input_vel;
|
|
|
|
}
|
|
|
|
pos_control->set_pos_vel_accel_xy(target_pos.topostype(), input_vel, accel);
|
2023-08-18 00:56:25 -03:00
|
|
|
|
2023-11-13 19:33:59 -04:00
|
|
|
// run pos controller
|
|
|
|
pos_control->update_xy_controller();
|
2023-08-18 00:56:25 -03:00
|
|
|
|
2023-11-13 19:33:59 -04:00
|
|
|
// call attitude controller
|
|
|
|
attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), target_yaw_rate, false);
|
2023-08-18 00:56:25 -03:00
|
|
|
|
2023-11-13 19:33:59 -04:00
|
|
|
// Send the commanded climb rate to the position controller
|
|
|
|
pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate);
|
2023-08-18 00:56:25 -03:00
|
|
|
|
|
|
|
// run the vertical position controller and set output throttle
|
|
|
|
pos_control->update_z_controller();
|
|
|
|
}
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
if (log_subsample <= 0) {
|
2019-07-29 04:55:40 -03:00
|
|
|
log_data();
|
2019-10-15 02:38:24 -03:00
|
|
|
if (copter.should_log(MASK_LOG_ATTITUDE_FAST) && copter.should_log(MASK_LOG_ATTITUDE_MED)) {
|
2019-07-29 04:55:40 -03:00
|
|
|
log_subsample = 1;
|
2019-10-15 02:38:24 -03:00
|
|
|
} else if (copter.should_log(MASK_LOG_ATTITUDE_FAST)) {
|
2019-07-29 04:55:40 -03:00
|
|
|
log_subsample = 2;
|
2019-10-15 02:38:24 -03:00
|
|
|
} else if (copter.should_log(MASK_LOG_ATTITUDE_MED)) {
|
2019-07-29 04:55:40 -03:00
|
|
|
log_subsample = 4;
|
|
|
|
} else {
|
|
|
|
log_subsample = 8;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
log_subsample -= 1;
|
|
|
|
}
|
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
// log system id and attitude
|
2021-02-01 12:26:21 -04:00
|
|
|
void ModeSystemId::log_data() const
|
2019-07-29 04:55:40 -03:00
|
|
|
{
|
|
|
|
Vector3f delta_angle;
|
2021-02-11 17:34:38 -04:00
|
|
|
float delta_angle_dt;
|
|
|
|
copter.ins.get_delta_angle(delta_angle, delta_angle_dt);
|
2019-07-29 04:55:40 -03:00
|
|
|
|
|
|
|
Vector3f delta_velocity;
|
2021-02-11 17:34:38 -04:00
|
|
|
float delta_velocity_dt;
|
|
|
|
copter.ins.get_delta_velocity(delta_velocity, delta_velocity_dt);
|
2019-07-29 04:55:40 -03:00
|
|
|
|
2019-10-15 02:38:24 -03:00
|
|
|
if (is_positive(delta_angle_dt) && is_positive(delta_velocity_dt)) {
|
2019-07-29 04:55:40 -03:00
|
|
|
copter.Log_Write_SysID_Data(waveform_time, waveform_sample, waveform_freq_rads / (2 * M_PI), degrees(delta_angle.x / delta_angle_dt), degrees(delta_angle.y / delta_angle_dt), degrees(delta_angle.z / delta_angle_dt), delta_velocity.x / delta_velocity_dt, delta_velocity.y / delta_velocity_dt, delta_velocity.z / delta_velocity_dt);
|
|
|
|
}
|
|
|
|
|
|
|
|
// Full rate logging of attitude, rate and pid loops
|
|
|
|
copter.Log_Write_Attitude();
|
2023-03-06 08:15:38 -04:00
|
|
|
copter.Log_Write_PIDS();
|
2023-08-18 00:56:25 -03:00
|
|
|
|
2024-02-13 23:26:31 -04:00
|
|
|
if (is_poscontrol_axis_type()) {
|
2023-08-18 00:56:25 -03:00
|
|
|
pos_control->write_log();
|
|
|
|
copter.logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x());
|
|
|
|
copter.logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y());
|
|
|
|
|
|
|
|
}
|
2019-07-29 04:55:40 -03:00
|
|
|
}
|
|
|
|
|
2024-02-13 23:26:31 -04:00
|
|
|
bool ModeSystemId::is_poscontrol_axis_type() const
|
|
|
|
{
|
|
|
|
bool ret = false;
|
|
|
|
|
2024-05-13 13:16:57 -03:00
|
|
|
switch ((AxisType)axis.get()) {
|
|
|
|
case AxisType::DISTURB_POS_LAT:
|
|
|
|
case AxisType::DISTURB_POS_LONG:
|
|
|
|
case AxisType::DISTURB_VEL_LAT:
|
|
|
|
case AxisType::DISTURB_VEL_LONG:
|
2024-05-13 20:31:42 -03:00
|
|
|
case AxisType::INPUT_VEL_LAT:
|
|
|
|
case AxisType::INPUT_VEL_LONG:
|
2024-05-13 13:16:57 -03:00
|
|
|
ret = true;
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
break;
|
|
|
|
}
|
2024-02-13 23:26:31 -04:00
|
|
|
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2019-07-29 04:55:40 -03:00
|
|
|
#endif
|