Sub: Limit input demand rate of change on motor mixer in manual mode

This commit is contained in:
Jacob Walser 2018-04-24 18:34:04 -04:00
parent 99cd11494e
commit 18d93a72ef
3 changed files with 7 additions and 0 deletions

View File

@ -320,6 +320,8 @@ private:
AP_Arming_Sub arming {ahrs, barometer, compass, battery};
uint32_t last_control_mode_update_us; // dt tracking for control mode updates
// Altitude
// The cm/s we are moving up or down based on filtered data - Positive = UP
int16_t climb_rate;

View File

@ -32,4 +32,7 @@ void Sub::manual_run()
motors.set_throttle(channel_throttle->norm_input());
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
float dt = ((float)(micros() - last_control_mode_update_us)) / 1e6;
motors.limit_demand_slew_rate(g.manual_slew_rate, dt);
}

View File

@ -139,6 +139,8 @@ void Sub::update_flight_mode()
default:
break;
}
last_control_mode_update_us = micros();
}
// exit_mode - high level call to organise cleanup as a flight mode is exited