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/libraries/AC_AttitudeControl/AC_AttitudeControl_TS.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
15
This class inherits from AC_AttitudeControl_Multi and provides functionality
16
specific to tailsitter quadplanes.
17
1) "body-frame" roll control mode for all tailsitters
18
2) a relax_attitude_controller method needed for coping with vectored tailsitters
19
*/
20
#include "AC_AttitudeControl_TS.h"
21
22
void AC_AttitudeControl_TS::relax_attitude_controllers(bool exclude_pitch)
23
{
24
// If exclude_pitch: relax roll and yaw rate controller outputs only,
25
// leaving pitch controller active to let TVBS motors tilt up while in throttle_wait
26
if (exclude_pitch) {
27
// Get the current attitude quaternion
28
Quaternion current_attitude;
29
_ahrs.get_quat_body_to_ned(current_attitude);
30
31
Vector3f current_eulers;
32
current_attitude.to_euler(current_eulers.x, current_eulers.y, current_eulers.z);
33
34
// set target attitude to zero pitch with (approximate) current roll and yaw
35
// by rotating the current_attitude quaternion by the error in desired pitch
36
Quaternion pitch_rotation;
37
pitch_rotation.from_axis_angle(Vector3f(0, -1, 0), current_eulers.y);
38
_attitude_target = current_attitude * pitch_rotation;
39
_attitude_target.normalize();
40
_attitude_target.to_euler(_euler_angle_target.x, _euler_angle_target.y, _euler_angle_target.z);
41
_attitude_ang_error = current_attitude.inverse() * _attitude_target;
42
43
// Initialize the roll and yaw angular rate variables to the current rate
44
_ang_vel_target = _ahrs.get_gyro();
45
ang_vel_to_euler_rate(_attitude_target, _ang_vel_target, _euler_rate_target);
46
_ang_vel_body.x = _ahrs.get_gyro().x;
47
_ang_vel_body.z = _ahrs.get_gyro().z;
48
49
// Reset the roll and yaw I terms
50
get_rate_roll_pid().reset_I();
51
get_rate_yaw_pid().reset_I();
52
} else {
53
// relax all attitude controllers
54
AC_AttitudeControl::relax_attitude_controllers();
55
}
56
}
57
58
// Command euler yaw rate and pitch angle with roll angle specified in body frame
59
// (used only by tailsitter quadplanes)
60
// If plane_controls is true, swap the effects of roll and yaw as euler pitch approaches 90 degrees
61
void AC_AttitudeControl_TS::input_euler_rate_yaw_euler_angle_pitch_bf_roll(bool plane_controls, float body_roll_cd, float euler_pitch_cd, float euler_yaw_rate_cds)
62
{
63
// Convert from centidegrees on public interface to radians
64
float euler_yaw_rate = radians(euler_yaw_rate_cds*0.01f);
65
float euler_pitch = radians(constrain_float(euler_pitch_cd * 0.01f, -90.0f, 90.0f));
66
float body_roll = radians(-body_roll_cd * 0.01f);
67
68
const float cpitch = cosf(euler_pitch);
69
const float spitch = fabsf(sinf(euler_pitch));
70
71
// Compute attitude error
72
Quaternion attitude_body;
73
Quaternion error_quat;
74
_ahrs.get_quat_body_to_ned(attitude_body);
75
error_quat = attitude_body.inverse() * _attitude_target;
76
Vector3f att_error;
77
error_quat.to_axis_angle(att_error);
78
79
// update heading
80
float yaw_rate = euler_yaw_rate;
81
if (plane_controls) {
82
yaw_rate = (euler_yaw_rate * spitch) + (body_roll * cpitch);
83
}
84
// limit yaw error
85
float yaw_error = fabsf(att_error.z);
86
float error_ratio = yaw_error / M_PI_2;
87
if (error_ratio > 1) {
88
yaw_rate /= (error_ratio * error_ratio);
89
}
90
_euler_angle_target.z = wrap_PI(_euler_angle_target.z + yaw_rate * _dt);
91
92
// init attitude target to desired euler yaw and pitch with zero roll
93
_attitude_target.from_euler(0, euler_pitch, _euler_angle_target.z);
94
95
// apply body-frame yaw/roll (this is roll/yaw for a tailsitter in forward flight)
96
// rotate body_roll axis by |sin(pitch angle)|
97
Quaternion bf_roll_Q;
98
bf_roll_Q.from_axis_angle(Vector3f(0, 0, spitch * body_roll));
99
100
// rotate body_yaw axis by cos(pitch angle)
101
Quaternion bf_yaw_Q;
102
if (plane_controls) {
103
bf_yaw_Q.from_axis_angle(Vector3f(cpitch, 0, 0), euler_yaw_rate);
104
} else {
105
bf_yaw_Q.from_axis_angle(Vector3f(-cpitch * body_roll, 0, 0));
106
}
107
_attitude_target = _attitude_target * bf_roll_Q * bf_yaw_Q;
108
109
// _euler_angle_target roll and pitch: Note: roll/yaw will be indeterminate when pitch is near +/-90
110
// These should be used only for logging target eulers, with the caveat noted above.
111
// Also note that _attitude_target.from_euler() should only be used in special circumstances
112
// such as when attitude is specified directly in terms of Euler angles.
113
// _euler_angle_target.x = _attitude_target.get_euler_roll();
114
// _euler_angle_target.y = euler_pitch;
115
116
// Set rate feedforward requests to zero
117
_euler_rate_target.zero();
118
_ang_vel_target.zero();
119
120
// Compute attitude error
121
error_quat = attitude_body.inverse() * _attitude_target;
122
error_quat.to_axis_angle(att_error);
123
124
// Compute the angular velocity target from the attitude error
125
_ang_vel_body = update_ang_vel_target_from_att_error(att_error);
126
}
127
128