mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
f84c855dd1
run motors output at rate thread loop rate allow rate thread to be enabled/disabled at runtime for in-flight impact testing setup the right PID notch sample rate when using the rate thread the PID notches run at a very different sample rate call update_dynamic_notch_at_specified_rate() in rate thread log RTDT messages to track rate loop performance set dt each cycle of the rate loop thread run rate controller on samples as soon as they are ready detect overload conditions in both the rate loop and main loop decimate the rate thread if the CPU appears overloaded decimate the gyro window inside the IMU add in gyro drift to attitude rate thread add fixed-rate thread option configure rate loop based on AP_INERTIALSENSOR_FAST_SAMPLE_WINDOW_ENABLED better rate loop thread decimation management ensure fix rate attitude is enabled on arming add rate loop timing debug update backend filters rather than all the backends provide more options around attitude rates only log attitude and IMU from main loop force trigger_groups() and reduce attitude thread priority migrate fast rate enablement to FSTRATE_ENABLE remove rate thread logging configuration and choose sensible logging rates conditionally compile rate thread pieces allow fast rate decimation to be user throttled if target rate changes immediately jump to target rate recover quickly from rate changes ensure fixed rate always prints the rate on arming and is always up to date add support for fixed rate attitude that does not change when disarmed only push to subsystems at main loop rate add logging and motor timing debug correctly round gyro decimation rates set dshot rate when changing attitude rate fallback to higher dshot rates at lower loop rates re-factor rate loop rate updates log rates in systemid mode reset target modifiers at loop rate don't compile in support on tradheli move rate thread into its own compilation unit add rate loop config abstraction that allows code to be elided on non-copter builds dynamically enable/disable rate thread correctly add design comment for the rate thread Co-authored-by: Andrew Tridgell <andrew@tridgell.net>
139 lines
4.8 KiB
C++
139 lines
4.8 KiB
C++
#include "Copter.h"
|
|
|
|
/*************************************************************
|
|
* Attitude Rate controllers and timing
|
|
****************************************************************/
|
|
|
|
/*
|
|
update rate controller when run from main thread (normal operation)
|
|
*/
|
|
void Copter::run_rate_controller_main()
|
|
{
|
|
// set attitude and position controller loop time
|
|
const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
|
|
pos_control->set_dt(last_loop_time_s);
|
|
attitude_control->set_dt(last_loop_time_s);
|
|
|
|
if (!using_rate_thread) {
|
|
motors->set_dt(last_loop_time_s);
|
|
// only run the rate controller if we are not using the rate thread
|
|
attitude_control->rate_controller_run();
|
|
}
|
|
// reset sysid and other temporary inputs
|
|
attitude_control->rate_controller_target_reset();
|
|
}
|
|
|
|
/*************************************************************
|
|
* throttle control
|
|
****************************************************************/
|
|
|
|
// update estimated throttle required to hover (if necessary)
|
|
// called at 100hz
|
|
void Copter::update_throttle_hover()
|
|
{
|
|
// if not armed or landed or on standby then exit
|
|
if (!motors->armed() || ap.land_complete || standby_active) {
|
|
return;
|
|
}
|
|
|
|
// do not update in manual throttle modes or Drift
|
|
if (flightmode->has_manual_throttle() || (copter.flightmode->mode_number() == Mode::Number::DRIFT)) {
|
|
return;
|
|
}
|
|
|
|
// do not update while climbing or descending
|
|
if (!is_zero(pos_control->get_vel_desired_cms().z)) {
|
|
return;
|
|
}
|
|
|
|
// get throttle output
|
|
float throttle = motors->get_throttle();
|
|
|
|
// calc average throttle if we are in a level hover. accounts for heli hover roll trim
|
|
if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z_up_cms()) < 60 &&
|
|
fabsf(ahrs.roll_sensor-attitude_control->get_roll_trim_cd()) < 500 && labs(ahrs.pitch_sensor) < 500) {
|
|
// Can we set the time constant automatically
|
|
motors->update_throttle_hover(0.01f);
|
|
#if HAL_GYROFFT_ENABLED
|
|
gyro_fft.update_freq_hover(0.01f, motors->get_throttle_out());
|
|
#endif
|
|
}
|
|
}
|
|
|
|
// get_pilot_desired_climb_rate - transform pilot's throttle input to climb rate in cm/s
|
|
// without any deadzone at the bottom
|
|
float Copter::get_pilot_desired_climb_rate(float throttle_control)
|
|
{
|
|
// throttle failsafe check
|
|
if (failsafe.radio || !rc().has_ever_seen_rc_input()) {
|
|
return 0.0f;
|
|
}
|
|
|
|
#if TOY_MODE_ENABLED
|
|
if (g2.toy_mode.enabled()) {
|
|
// allow throttle to be reduced after throttle arming and for
|
|
// slower descent close to the ground
|
|
g2.toy_mode.throttle_adjust(throttle_control);
|
|
}
|
|
#endif
|
|
|
|
// ensure a reasonable throttle value
|
|
throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
|
|
|
|
// ensure a reasonable deadzone
|
|
g.throttle_deadzone.set(constrain_int16(g.throttle_deadzone, 0, 400));
|
|
|
|
float desired_rate = 0.0f;
|
|
const float mid_stick = get_throttle_mid();
|
|
const float deadband_top = mid_stick + g.throttle_deadzone;
|
|
const float deadband_bottom = mid_stick - g.throttle_deadzone;
|
|
|
|
// check throttle is above, below or in the deadband
|
|
if (throttle_control < deadband_bottom) {
|
|
// below the deadband
|
|
desired_rate = get_pilot_speed_dn() * (throttle_control-deadband_bottom) / deadband_bottom;
|
|
} else if (throttle_control > deadband_top) {
|
|
// above the deadband
|
|
desired_rate = g.pilot_speed_up * (throttle_control-deadband_top) / (1000.0f-deadband_top);
|
|
} else {
|
|
// must be in the deadband
|
|
desired_rate = 0.0f;
|
|
}
|
|
|
|
return desired_rate;
|
|
}
|
|
|
|
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
|
|
float Copter::get_non_takeoff_throttle()
|
|
{
|
|
return MAX(0,motors->get_throttle_hover()/2.0f);
|
|
}
|
|
|
|
// set_accel_throttle_I_from_pilot_throttle - smoothes transition from pilot controlled throttle to autopilot throttle
|
|
void Copter::set_accel_throttle_I_from_pilot_throttle()
|
|
{
|
|
// get last throttle input sent to attitude controller
|
|
float pilot_throttle = constrain_float(attitude_control->get_throttle_in(), 0.0f, 1.0f);
|
|
// shift difference between pilot's throttle and hover throttle into accelerometer I
|
|
pos_control->get_accel_z_pid().set_integrator((pilot_throttle-motors->get_throttle_hover()) * 1000.0f);
|
|
}
|
|
|
|
// rotate vector from vehicle's perspective to North-East frame
|
|
void Copter::rotate_body_frame_to_NE(float &x, float &y)
|
|
{
|
|
float ne_x = x*ahrs.cos_yaw() - y*ahrs.sin_yaw();
|
|
float ne_y = x*ahrs.sin_yaw() + y*ahrs.cos_yaw();
|
|
x = ne_x;
|
|
y = ne_y;
|
|
}
|
|
|
|
// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
|
|
uint16_t Copter::get_pilot_speed_dn() const
|
|
{
|
|
if (g2.pilot_speed_dn == 0) {
|
|
return abs(g.pilot_speed_up);
|
|
} else {
|
|
return abs(g2.pilot_speed_dn);
|
|
}
|
|
}
|