AP_Logger: log IOMCU cpu id and mcu id
[ardupilot.git] / ArduCopter / mode_systemid.cpp
blob1462454b78279bacae27a0d24d5d23ac5f203340
1 #include "Copter.h"
2 #include <AP_Math/control.h>
4 #if MODE_SYSTEMID_ENABLED
6 /*
7 * Init and run calls for systemId, flight mode
8 */
10 const AP_Param::GroupInfo ModeSystemId::var_info[] = {
12 // @Param: _AXIS
13 // @DisplayName: System identification axis
14 // @Description: Controls which axis are being excited. Set to non-zero to see more parameters
15 // @User: Standard
16 // @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
17 AP_GROUPINFO_FLAGS("_AXIS", 1, ModeSystemId, axis, 0, AP_PARAM_FLAG_ENABLE),
19 // @Param: _MAGNITUDE
20 // @DisplayName: System identification Chirp Magnitude
21 // @Description: Magnitude of sweep in deg, deg/s and 0-1 for mixer outputs.
22 // @User: Standard
23 AP_GROUPINFO("_MAGNITUDE", 2, ModeSystemId, waveform_magnitude, 15),
25 // @Param: _F_START_HZ
26 // @DisplayName: System identification Start Frequency
27 // @Description: Frequency at the start of the sweep
28 // @Range: 0.01 100
29 // @Units: Hz
30 // @User: Standard
31 AP_GROUPINFO("_F_START_HZ", 3, ModeSystemId, frequency_start, 0.5f),
33 // @Param: _F_STOP_HZ
34 // @DisplayName: System identification Stop Frequency
35 // @Description: Frequency at the end of the sweep
36 // @Range: 0.01 100
37 // @Units: Hz
38 // @User: Standard
39 AP_GROUPINFO("_F_STOP_HZ", 4, ModeSystemId, frequency_stop, 40),
41 // @Param: _T_FADE_IN
42 // @DisplayName: System identification Fade in time
43 // @Description: Time to reach maximum amplitude of sweep
44 // @Range: 0 20
45 // @Units: s
46 // @User: Standard
47 AP_GROUPINFO("_T_FADE_IN", 5, ModeSystemId, time_fade_in, 15),
49 // @Param: _T_REC
50 // @DisplayName: System identification Total Sweep length
51 // @Description: Time taken to complete the sweep
52 // @Range: 0 255
53 // @Units: s
54 // @User: Standard
55 AP_GROUPINFO("_T_REC", 6, ModeSystemId, time_record, 70),
57 // @Param: _T_FADE_OUT
58 // @DisplayName: System identification Fade out time
59 // @Description: Time to reach zero amplitude at the end of the sweep
60 // @Range: 0 5
61 // @Units: s
62 // @User: Standard
63 AP_GROUPINFO("_T_FADE_OUT", 7, ModeSystemId, time_fade_out, 2),
65 AP_GROUPEND
68 ModeSystemId::ModeSystemId(void) : Mode()
70 AP_Param::setup_object_defaults(this, var_info);
73 #define SYSTEM_ID_DELAY 1.0f // time in seconds waited after system id mode change for frequency sweep injection
75 // systemId_init - initialise systemId controller
76 bool ModeSystemId::init(bool ignore_checks)
78 // check if enabled
79 if (axis == 0) {
80 gcs().send_text(MAV_SEVERITY_WARNING, "No axis selected, SID_AXIS = 0");
81 return false;
84 // ensure we are flying
85 if (!copter.motors->armed() || !copter.ap.auto_armed || copter.ap.land_complete) {
86 gcs().send_text(MAV_SEVERITY_WARNING, "Aircraft must be flying");
87 return false;
90 if (!is_poscontrol_axis_type()) {
92 // System ID is being done on the attitude control loops
94 // Can only switch into System ID Axes 1-13 with a flight mode that has manual throttle
95 if (!copter.flightmode->has_manual_throttle()) {
96 gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires manual throttle");
97 return false;
100 #if FRAME_CONFIG == HELI_FRAME
101 copter.input_manager.set_use_stab_col(true);
102 #endif
104 } else {
106 // System ID is being done on the position control loops
108 // Can only switch into System ID Axes 14-19 from Loiter flight mode
109 if (copter.flightmode->mode_number() != Mode::Number::LOITER) {
110 gcs().send_text(MAV_SEVERITY_WARNING, "Axis requires switch from Loiter");
111 return false;
114 // set horizontal speed and acceleration limits
115 pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
116 pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
118 // initialise the horizontal position controller
119 if (!pos_control->is_active_xy()) {
120 pos_control->init_xy_controller();
123 // set vertical speed and acceleration limits
124 pos_control->set_max_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
125 pos_control->set_correction_speed_accel_z(wp_nav->get_default_speed_down(), wp_nav->get_default_speed_up(), wp_nav->get_accel_z());
127 // initialise the vertical position controller
128 if (!pos_control->is_active_z()) {
129 pos_control->init_z_controller();
131 Vector3f curr_pos;
132 curr_pos = inertial_nav.get_position_neu_cm();
133 target_pos = curr_pos.xy();
136 att_bf_feedforward = attitude_control->get_bf_feedforward();
137 waveform_time = 0.0f;
138 time_const_freq = 2.0f / frequency_start; // Two full cycles at the starting frequency
139 systemid_state = SystemIDModeState::SYSTEMID_STATE_TESTING;
140 log_subsample = 0;
142 chirp_input.init(time_record, frequency_start, frequency_stop, time_fade_in, time_fade_out, time_const_freq);
144 gcs().send_text(MAV_SEVERITY_INFO, "SystemID Starting: axis=%d", (unsigned)axis);
146 #if HAL_LOGGING_ENABLED
147 copter.Log_Write_SysID_Setup(axis, waveform_magnitude, frequency_start, frequency_stop, time_fade_in, time_const_freq, time_record, time_fade_out);
148 #endif
150 return true;
153 // systemId_exit - clean up systemId controller before exiting
154 void ModeSystemId::exit()
156 // reset the feedforward enabled parameter to the initialized state
157 attitude_control->bf_feedforward(att_bf_feedforward);
160 // systemId_run - runs the systemId controller
161 // should be called at 100hz or more
162 void ModeSystemId::run()
164 float target_roll, target_pitch;
165 float target_yaw_rate = 0.0f;
166 float pilot_throttle_scaled = 0.0f;
167 float target_climb_rate = 0.0f;
168 Vector2f input_vel;
170 if (!is_poscontrol_axis_type()) {
172 // apply simple mode transform to pilot inputs
173 update_simple_mode();
175 // convert pilot input to lean angles
176 get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
178 // get pilot's desired yaw rate
179 target_yaw_rate = get_pilot_desired_yaw_rate();
181 if (!motors->armed()) {
182 // Motors should be Stopped
183 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
184 // Tradheli doesn't set spool state to ground idle when throttle stick is zero. Ground idle only set when
185 // motor interlock is disabled.
186 } else if (copter.ap.throttle_zero && !copter.is_tradheli()) {
187 // Attempting to Land
188 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
189 } else {
190 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
193 switch (motors->get_spool_state()) {
194 case AP_Motors::SpoolState::SHUT_DOWN:
195 // Motors Stopped
196 attitude_control->reset_yaw_target_and_rate();
197 attitude_control->reset_rate_controller_I_terms();
198 break;
200 case AP_Motors::SpoolState::GROUND_IDLE:
201 // Landed
202 // Tradheli initializes targets when going from disarmed to armed state.
203 // init_targets_on_arming is always set true for multicopter.
204 if (motors->init_targets_on_arming()) {
205 attitude_control->reset_yaw_target_and_rate();
206 attitude_control->reset_rate_controller_I_terms_smoothly();
208 break;
210 case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
211 // clear landing flag above zero throttle
212 if (!motors->limit.throttle_lower) {
213 set_land_complete(false);
215 break;
217 case AP_Motors::SpoolState::SPOOLING_UP:
218 case AP_Motors::SpoolState::SPOOLING_DOWN:
219 // do nothing
220 break;
223 // get pilot's desired throttle
224 #if FRAME_CONFIG == HELI_FRAME
225 pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
226 #else
227 pilot_throttle_scaled = get_pilot_desired_throttle();
228 #endif
232 if ((systemid_state == SystemIDModeState::SYSTEMID_STATE_TESTING) &&
233 (!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))) {
234 systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
235 gcs().send_text(MAV_SEVERITY_INFO, "SystemID Parameter Error");
238 waveform_time += G_Dt;
239 waveform_sample = chirp_input.update(waveform_time - SYSTEM_ID_DELAY, waveform_magnitude);
240 waveform_freq_rads = chirp_input.get_frequency_rads();
241 Vector2f disturb_state;
242 switch (systemid_state) {
243 case SystemIDModeState::SYSTEMID_STATE_STOPPED:
244 attitude_control->bf_feedforward(att_bf_feedforward);
245 break;
246 case SystemIDModeState::SYSTEMID_STATE_TESTING:
248 if (copter.ap.land_complete) {
249 systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
250 gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: Landed");
251 break;
253 if (attitude_control->lean_angle_deg()*100 > attitude_control->lean_angle_max_cd()) {
254 systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
255 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());
256 break;
258 if (waveform_time > SYSTEM_ID_DELAY + time_fade_in + time_const_freq + time_record + time_fade_out) {
259 systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
260 gcs().send_text(MAV_SEVERITY_INFO, "SystemID Finished");
261 break;
264 switch ((AxisType)axis.get()) {
265 case AxisType::NONE:
266 systemid_state = SystemIDModeState::SYSTEMID_STATE_STOPPED;
267 gcs().send_text(MAV_SEVERITY_INFO, "SystemID Stopped: axis = 0");
268 break;
269 case AxisType::INPUT_ROLL:
270 target_roll += waveform_sample*100.0f;
271 break;
272 case AxisType::INPUT_PITCH:
273 target_pitch += waveform_sample*100.0f;
274 break;
275 case AxisType::INPUT_YAW:
276 target_yaw_rate += waveform_sample*100.0f;
277 break;
278 case AxisType::RECOVER_ROLL:
279 target_roll += waveform_sample*100.0f;
280 attitude_control->bf_feedforward(false);
281 break;
282 case AxisType::RECOVER_PITCH:
283 target_pitch += waveform_sample*100.0f;
284 attitude_control->bf_feedforward(false);
285 break;
286 case AxisType::RECOVER_YAW:
287 target_yaw_rate += waveform_sample*100.0f;
288 attitude_control->bf_feedforward(false);
289 break;
290 case AxisType::RATE_ROLL:
291 attitude_control->rate_bf_roll_sysid(radians(waveform_sample));
292 break;
293 case AxisType::RATE_PITCH:
294 attitude_control->rate_bf_pitch_sysid(radians(waveform_sample));
295 break;
296 case AxisType::RATE_YAW:
297 attitude_control->rate_bf_yaw_sysid(radians(waveform_sample));
298 break;
299 case AxisType::MIX_ROLL:
300 attitude_control->actuator_roll_sysid(waveform_sample);
301 break;
302 case AxisType::MIX_PITCH:
303 attitude_control->actuator_pitch_sysid(waveform_sample);
304 break;
305 case AxisType::MIX_YAW:
306 attitude_control->actuator_yaw_sysid(waveform_sample);
307 break;
308 case AxisType::MIX_THROTTLE:
309 pilot_throttle_scaled += waveform_sample;
310 break;
311 case AxisType::DISTURB_POS_LAT:
312 disturb_state.x = 0.0f;
313 disturb_state.y = waveform_sample * 100.0f;
314 disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
315 pos_control->set_disturb_pos_cm(disturb_state);
316 break;
317 case AxisType::DISTURB_POS_LONG:
318 disturb_state.x = waveform_sample * 100.0f;
319 disturb_state.y = 0.0f;
320 disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
321 pos_control->set_disturb_pos_cm(disturb_state);
322 break;
323 case AxisType::DISTURB_VEL_LAT:
324 disturb_state.x = 0.0f;
325 disturb_state.y = waveform_sample * 100.0f;
326 disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
327 pos_control->set_disturb_vel_cms(disturb_state);
328 break;
329 case AxisType::DISTURB_VEL_LONG:
330 disturb_state.x = waveform_sample * 100.0f;
331 disturb_state.y = 0.0f;
332 disturb_state.rotate(attitude_control->get_att_target_euler_rad().z);
333 pos_control->set_disturb_vel_cms(disturb_state);
334 break;
335 case AxisType::INPUT_VEL_LAT:
336 input_vel.x = 0.0f;
337 input_vel.y = waveform_sample * 100.0f;
338 input_vel.rotate(attitude_control->get_att_target_euler_rad().z);
339 break;
340 case AxisType::INPUT_VEL_LONG:
341 input_vel.x = waveform_sample * 100.0f;
342 input_vel.y = 0.0f;
343 input_vel.rotate(attitude_control->get_att_target_euler_rad().z);
344 break;
346 break;
349 if (!is_poscontrol_axis_type()) {
351 // call attitude controller
352 attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
354 // output pilot's throttle
355 attitude_control->set_throttle_out(pilot_throttle_scaled, !copter.is_tradheli(), g.throttle_filt);
357 } else {
359 // relax loiter target if we might be landed
360 if (copter.ap.land_complete_maybe) {
361 pos_control->soften_for_landing_xy();
364 Vector2f accel;
365 target_pos += input_vel * G_Dt;
366 if (is_positive(G_Dt)) {
367 accel = (input_vel - input_vel_last) / G_Dt;
368 input_vel_last = input_vel;
370 pos_control->set_pos_vel_accel_xy(target_pos.topostype(), input_vel, accel);
372 // run pos controller
373 pos_control->update_xy_controller();
375 // call attitude controller
376 attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), target_yaw_rate, false);
378 // Send the commanded climb rate to the position controller
379 pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate);
381 // run the vertical position controller and set output throttle
382 pos_control->update_z_controller();
385 if (log_subsample <= 0) {
386 log_data();
387 if (copter.should_log(MASK_LOG_ATTITUDE_FAST) && copter.should_log(MASK_LOG_ATTITUDE_MED)) {
388 log_subsample = 1;
389 } else if (copter.should_log(MASK_LOG_ATTITUDE_FAST)) {
390 log_subsample = 2;
391 } else if (copter.should_log(MASK_LOG_ATTITUDE_MED)) {
392 log_subsample = 4;
393 } else {
394 log_subsample = 8;
397 log_subsample -= 1;
400 // log system id and attitude
401 void ModeSystemId::log_data() const
403 Vector3f delta_angle;
404 float delta_angle_dt;
405 copter.ins.get_delta_angle(delta_angle, delta_angle_dt);
407 Vector3f delta_velocity;
408 float delta_velocity_dt;
409 copter.ins.get_delta_velocity(delta_velocity, delta_velocity_dt);
411 if (is_positive(delta_angle_dt) && is_positive(delta_velocity_dt)) {
412 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);
415 // Full rate logging of attitude, rate and pid loops
416 copter.Log_Write_Attitude();
417 copter.Log_Write_Rate();
418 copter.Log_Write_PIDS();
420 if (is_poscontrol_axis_type()) {
421 pos_control->write_log();
422 copter.logger.Write_PID(LOG_PIDN_MSG, pos_control->get_vel_xy_pid().get_pid_info_x());
423 copter.logger.Write_PID(LOG_PIDE_MSG, pos_control->get_vel_xy_pid().get_pid_info_y());
428 bool ModeSystemId::is_poscontrol_axis_type() const
430 bool ret = false;
432 switch ((AxisType)axis.get()) {
433 case AxisType::DISTURB_POS_LAT:
434 case AxisType::DISTURB_POS_LONG:
435 case AxisType::DISTURB_VEL_LAT:
436 case AxisType::DISTURB_VEL_LONG:
437 case AxisType::INPUT_VEL_LAT:
438 case AxisType::INPUT_VEL_LONG:
439 ret = true;
440 break;
441 default:
442 break;
445 return ret;
448 #endif