Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/Attitude.cpp
9317 views
1
#include "Copter.h"
2
3
/*************************************************************
4
* Attitude Rate controllers and timing
5
****************************************************************/
6
7
/*
8
update rate controller when run from main thread (normal operation)
9
*/
10
void Copter::run_rate_controller_main()
11
{
12
// set attitude and position controller loop time
13
const float last_loop_time_s = AP::scheduler().get_last_loop_time_s();
14
pos_control->set_dt_s(last_loop_time_s);
15
attitude_control->set_dt_s(last_loop_time_s);
16
17
if (!using_rate_thread) {
18
motors->set_dt_s(last_loop_time_s);
19
// only run the rate controller if we are not using the rate thread
20
attitude_control->rate_controller_run();
21
}
22
// reset sysid and other temporary inputs
23
attitude_control->rate_controller_target_reset();
24
}
25
26
/*************************************************************
27
* throttle control
28
****************************************************************/
29
30
// update estimated throttle required to hover (if necessary)
31
// called at 100hz
32
void Copter::update_throttle_hover()
33
{
34
// if not armed or landed or on standby then exit
35
if (!motors->armed() || ap.land_complete || standby_active) {
36
return;
37
}
38
39
// do not update in manual throttle modes or Drift
40
if (flightmode->has_manual_throttle() || (copter.flightmode->mode_number() == Mode::Number::DRIFT)) {
41
return;
42
}
43
44
// do not update while climbing or descending
45
if (!is_zero(pos_control->get_vel_desired_U_ms())) {
46
return;
47
}
48
49
// do not update if no vertical velocity estimate
50
float vel_d_ms;
51
if (!AP::ahrs().get_velocity_D(vel_d_ms, vibration_check.high_vibes)) {
52
return;
53
}
54
55
// get throttle output
56
float throttle = motors->get_throttle();
57
58
// calc average throttle if we are in a level hover. accounts for heli hover roll trim
59
if ((throttle > 0.0f) && (fabsf(vel_d_ms) < 0.6) &&
60
(fabsf(ahrs.get_roll_rad() - attitude_control->get_roll_trim_rad()) < radians(5)) && (fabsf(ahrs.get_pitch_rad()) < radians(5))) {
61
// Can we set the time constant automatically
62
motors->update_throttle_hover(0.01f);
63
#if HAL_GYROFFT_ENABLED
64
gyro_fft.update_freq_hover(0.01f, motors->get_throttle_out());
65
#endif
66
}
67
}
68
69
// get_pilot_desired_climb_rate_ms - transform pilot's throttle input to climb rate in cm/s
70
// without any deadzone at the bottom
71
float Copter::get_pilot_desired_climb_rate_ms()
72
{
73
// throttle failsafe check
74
if (!rc().has_valid_input()) {
75
return 0.0f;
76
}
77
78
float throttle_control = copter.channel_throttle->get_control_in();
79
80
#if TOY_MODE_ENABLED
81
if (g2.toy_mode.enabled()) {
82
// allow throttle to be reduced after throttle arming and for
83
// slower descent close to the ground
84
g2.toy_mode.throttle_adjust(throttle_control);
85
}
86
#endif
87
88
// ensure a reasonable throttle value
89
throttle_control = constrain_float(throttle_control, 0.0f, 1000.0f);
90
91
// ensure a reasonable deadzone
92
g.throttle_deadzone.set(constrain_int16(g.throttle_deadzone, 0, 400));
93
94
float desired_rate_ms = 0.0f;
95
const float mid_stick = get_throttle_mid();
96
const float deadband_top = mid_stick + g.throttle_deadzone;
97
const float deadband_bottom = mid_stick - g.throttle_deadzone;
98
99
// check throttle is above, below or in the deadband
100
if (throttle_control < deadband_bottom) {
101
// below the deadband
102
desired_rate_ms = get_pilot_speed_dn() * 0.01 * (throttle_control - deadband_bottom) / deadband_bottom;
103
} else if (throttle_control > deadband_top) {
104
// above the deadband
105
desired_rate_ms = g.pilot_speed_up_cms * 0.01 * (throttle_control - deadband_top) / (1000.0 - deadband_top);
106
} else {
107
// must be in the deadband
108
desired_rate_ms = 0.0f;
109
}
110
111
return desired_rate_ms;
112
}
113
114
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
115
float Copter::get_non_takeoff_throttle()
116
{
117
return MAX(0,motors->get_throttle_hover() / 2.0);
118
}
119
120
// set_accel_throttle_I_from_pilot_throttle - smoothes transition from pilot controlled throttle to autopilot throttle
121
void Copter::set_accel_throttle_I_from_pilot_throttle()
122
{
123
// get last throttle input sent to attitude controller
124
float pilot_throttle = constrain_float(attitude_control->get_throttle_in(), 0.0, 1.0);
125
// shift difference between pilot's throttle and hover throttle into accelerometer I
126
pos_control->D_get_accel_pid().set_integrator(-(pilot_throttle - motors->get_throttle_hover()));
127
}
128
129
// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
130
uint16_t Copter::get_pilot_speed_dn() const
131
{
132
if (g2.pilot_speed_dn_cms == 0) {
133
return abs(g.pilot_speed_up_cms);
134
} else {
135
return abs(g2.pilot_speed_dn_cms);
136
}
137
}
138
139