Copter: change input_loiter_xxx to input_vel_xxx in sysid mode

This commit is contained in:
bnsgeyer 2024-05-13 19:31:42 -04:00 committed by Bill Geyer
parent bbaf557457
commit a1a5647b7f
2 changed files with 6 additions and 6 deletions

View File

@ -1653,8 +1653,8 @@ private:
DISTURB_POS_LONG = 15, // longitudinal body axis measured position is being excited
DISTURB_VEL_LAT = 16, // lateral body axis measured velocity is being excited
DISTURB_VEL_LONG = 17, // longitudinal body axis measured velocity is being excited
INPUT_LOITER_LAT = 18, // lateral body axis commanded velocity is being excited
INPUT_LOITER_LONG = 19, // longitudinal body axis commanded velocity is being excited
INPUT_VEL_LAT = 18, // lateral body axis commanded velocity is being excited
INPUT_VEL_LONG = 19, // longitudinal body axis commanded velocity is being excited
};
AP_Int8 axis; // Controls which axis are being excited. Set to non-zero to display other parameters

View File

@ -332,12 +332,12 @@ void ModeSystemId::run()
disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
pos_control->set_disturb_vel_cms(disturb_state);
break;
case AxisType::INPUT_LOITER_LAT:
case AxisType::INPUT_VEL_LAT:
input_vel.x = 0.0f;
input_vel.y = waveform_sample * 100.0f;
input_vel.rotate(attitude_control->get_att_target_euler_rad().z);
break;
case AxisType::INPUT_LOITER_LONG:
case AxisType::INPUT_VEL_LONG:
input_vel.x = waveform_sample * 100.0f;
input_vel.y = 0.0f;
input_vel.rotate(attitude_control->get_att_target_euler_rad().z);
@ -433,8 +433,8 @@ bool ModeSystemId::is_poscontrol_axis_type() const
case AxisType::DISTURB_POS_LONG:
case AxisType::DISTURB_VEL_LAT:
case AxisType::DISTURB_VEL_LONG:
case AxisType::INPUT_LOITER_LAT:
case AxisType::INPUT_LOITER_LONG:
case AxisType::INPUT_VEL_LAT:
case AxisType::INPUT_VEL_LONG:
ret = true;
break;
default: