mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Limit input demand rate of change on motor mixer in manual mode
This commit is contained in:
parent
99cd11494e
commit
18d93a72ef
@ -320,6 +320,8 @@ private:
|
|||||||
|
|
||||||
AP_Arming_Sub arming {ahrs, barometer, compass, battery};
|
AP_Arming_Sub arming {ahrs, barometer, compass, battery};
|
||||||
|
|
||||||
|
uint32_t last_control_mode_update_us; // dt tracking for control mode updates
|
||||||
|
|
||||||
// Altitude
|
// Altitude
|
||||||
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
||||||
int16_t climb_rate;
|
int16_t climb_rate;
|
||||||
|
@ -32,4 +32,7 @@ void Sub::manual_run()
|
|||||||
motors.set_throttle(channel_throttle->norm_input());
|
motors.set_throttle(channel_throttle->norm_input());
|
||||||
motors.set_forward(channel_forward->norm_input());
|
motors.set_forward(channel_forward->norm_input());
|
||||||
motors.set_lateral(channel_lateral->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);
|
||||||
}
|
}
|
||||||
|
@ -139,6 +139,8 @@ void Sub::update_flight_mode()
|
|||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
last_control_mode_update_us = micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
// exit_mode - high level call to organise cleanup as a flight mode is exited
|
// exit_mode - high level call to organise cleanup as a flight mode is exited
|
||||||
|
Loading…
Reference in New Issue
Block a user