CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduCopter/Attitude.cpp
Views: 1798
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(last_loop_time_s);
15
attitude_control->set_dt(last_loop_time_s);
16
17
if (!using_rate_thread) {
18
motors->set_dt(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_cms().z)) {
46
return;
47
}
48
49
// get throttle output
50
float throttle = motors->get_throttle();
51
52
// calc average throttle if we are in a level hover. accounts for heli hover roll trim
53
if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z_up_cms()) < 60 &&
54
fabsf(ahrs.roll_sensor-attitude_control->get_roll_trim_cd()) < 500 && labs(ahrs.pitch_sensor) < 500) {
55
// Can we set the time constant automatically
56
motors->update_throttle_hover(0.01f);
57
#if HAL_GYROFFT_ENABLED
58
gyro_fft.update_freq_hover(0.01f, motors->get_throttle_out());
59
#endif
60
}
61
}
62
63
// get_pilot_desired_climb_rate - transform pilot's throttle input to climb rate in cm/s
64
// without any deadzone at the bottom
65
float Copter::get_pilot_desired_climb_rate(float throttle_control)
66
{
67
// throttle failsafe check
68
if (failsafe.radio || !rc().has_ever_seen_rc_input()) {
69
return 0.0f;
70
}
71
72
#if TOY_MODE_ENABLED
73
if (g2.toy_mode.enabled()) {
74
// allow throttle to be reduced after throttle arming and for
75
// slower descent close to the ground
76
g2.toy_mode.throttle_adjust(throttle_control);
77
}
78
#endif
79
80
// ensure a reasonable throttle value
81
throttle_control = constrain_float(throttle_control,0.0f,1000.0f);
82
83
// ensure a reasonable deadzone
84
g.throttle_deadzone.set(constrain_int16(g.throttle_deadzone, 0, 400));
85
86
float desired_rate = 0.0f;
87
const float mid_stick = get_throttle_mid();
88
const float deadband_top = mid_stick + g.throttle_deadzone;
89
const float deadband_bottom = mid_stick - g.throttle_deadzone;
90
91
// check throttle is above, below or in the deadband
92
if (throttle_control < deadband_bottom) {
93
// below the deadband
94
desired_rate = get_pilot_speed_dn() * (throttle_control-deadband_bottom) / deadband_bottom;
95
} else if (throttle_control > deadband_top) {
96
// above the deadband
97
desired_rate = g.pilot_speed_up * (throttle_control-deadband_top) / (1000.0f-deadband_top);
98
} else {
99
// must be in the deadband
100
desired_rate = 0.0f;
101
}
102
103
return desired_rate;
104
}
105
106
// get_non_takeoff_throttle - a throttle somewhere between min and mid throttle which should not lead to a takeoff
107
float Copter::get_non_takeoff_throttle()
108
{
109
return MAX(0,motors->get_throttle_hover()/2.0f);
110
}
111
112
// set_accel_throttle_I_from_pilot_throttle - smoothes transition from pilot controlled throttle to autopilot throttle
113
void Copter::set_accel_throttle_I_from_pilot_throttle()
114
{
115
// get last throttle input sent to attitude controller
116
float pilot_throttle = constrain_float(attitude_control->get_throttle_in(), 0.0f, 1.0f);
117
// shift difference between pilot's throttle and hover throttle into accelerometer I
118
pos_control->get_accel_z_pid().set_integrator((pilot_throttle-motors->get_throttle_hover()) * 1000.0f);
119
}
120
121
// rotate vector from vehicle's perspective to North-East frame
122
void Copter::rotate_body_frame_to_NE(float &x, float &y)
123
{
124
float ne_x = x*ahrs.cos_yaw() - y*ahrs.sin_yaw();
125
float ne_y = x*ahrs.sin_yaw() + y*ahrs.cos_yaw();
126
x = ne_x;
127
y = ne_y;
128
}
129
130
// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
131
uint16_t Copter::get_pilot_speed_dn() const
132
{
133
if (g2.pilot_speed_dn == 0) {
134
return abs(g.pilot_speed_up);
135
} else {
136
return abs(g2.pilot_speed_dn);
137
}
138
}
139
140