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_Multi_6DoF.cpp
Views: 1798
1
#include <AP_Scripting/AP_Scripting_config.h>
2
3
#if AP_SCRIPTING_ENABLED
4
5
#include "AC_AttitudeControl_Multi_6DoF.h"
6
#include <AP_HAL/AP_HAL.h>
7
#include <AP_Math/AP_Math.h>
8
9
// 6DoF control is extracted from the existing copter code by treating desired angles as thrust angles rather than vehicle attitude.
10
// Vehicle attitude is then set separately, typically the vehicle would maintain 0 roll and pitch.
11
// rate commands result in the vehicle behaving as a ordinary copter.
12
13
// run lowest level body-frame rate controller and send outputs to the motors
14
void AC_AttitudeControl_Multi_6DoF::rate_controller_run() {
15
16
// pass current offsets to motors and run baseclass controller
17
// motors require the offsets to know which way is up
18
float roll_deg = roll_offset_deg;
19
float pitch_deg = pitch_offset_deg;
20
// if 6DoF control, always point directly up
21
// this stops horizontal drift due to error between target and true attitude
22
if (lateral_enable) {
23
roll_deg = degrees(AP::ahrs().get_roll());
24
}
25
if (forward_enable) {
26
pitch_deg = degrees(AP::ahrs().get_pitch());
27
}
28
_motors.set_roll_pitch(roll_deg,pitch_deg);
29
30
AC_AttitudeControl_Multi::rate_controller_run();
31
}
32
33
/*
34
override all input to the attitude controller and convert desired angles into thrust angles and substitute
35
*/
36
37
// Command an euler roll and pitch angle and an euler yaw rate with angular velocity feedforward and smoothing
38
void AC_AttitudeControl_Multi_6DoF::input_euler_angle_roll_pitch_euler_rate_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds) {
39
40
set_forward_lateral(euler_pitch_angle_cd, euler_roll_angle_cd);
41
42
AC_AttitudeControl_Multi::input_euler_angle_roll_pitch_euler_rate_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_rate_cds);
43
}
44
45
// Command an euler roll, pitch and yaw angle with angular velocity feedforward and smoothing
46
void AC_AttitudeControl_Multi_6DoF::input_euler_angle_roll_pitch_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, bool slew_yaw) {
47
48
set_forward_lateral(euler_pitch_angle_cd, euler_roll_angle_cd);
49
50
AC_AttitudeControl_Multi::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, slew_yaw);
51
}
52
53
// Command a thrust vector and heading rate
54
void AC_AttitudeControl_Multi_6DoF::input_thrust_vector_rate_heading(const Vector3f& thrust_vector, float heading_rate_cds, bool slew_yaw)
55
{
56
// convert thrust vector to a roll and pitch angles
57
// this negates the advantage of using thrust vector control, but works just fine
58
Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();
59
60
input_euler_angle_roll_pitch_euler_rate_yaw(degrees(angle_target.x) * 100.0f, degrees(angle_target.y) * 100.0f, heading_rate_cds);
61
}
62
63
// Command a thrust vector, heading and heading rate
64
void AC_AttitudeControl_Multi_6DoF::input_thrust_vector_heading(const Vector3f& thrust_vector, float heading_angle_cd, float heading_rate_cds)
65
{
66
// convert thrust vector to a roll and pitch angles
67
Vector3f angle_target = attitude_from_thrust_vector(thrust_vector, _ahrs.yaw).to_vector312();
68
69
// note that we are throwing away heading rate here
70
input_euler_angle_roll_pitch_yaw(degrees(angle_target.x) * 100.0f, degrees(angle_target.y) * 100.0f, heading_angle_cd, true);
71
}
72
73
void AC_AttitudeControl_Multi_6DoF::set_forward_lateral(float &euler_pitch_angle_cd, float &euler_roll_angle_cd)
74
{
75
// pitch/forward
76
if (forward_enable) {
77
_motors.set_forward(-sinf(radians(euler_pitch_angle_cd * 0.01f)));
78
euler_pitch_angle_cd = pitch_offset_deg * 100.0f;
79
} else {
80
_motors.set_forward(0.0f);
81
euler_pitch_angle_cd += pitch_offset_deg * 100.0f;
82
}
83
euler_pitch_angle_cd = wrap_180_cd(euler_pitch_angle_cd);
84
85
// roll/lateral
86
if (lateral_enable) {
87
_motors.set_lateral(sinf(radians(euler_roll_angle_cd * 0.01f)));
88
euler_roll_angle_cd = roll_offset_deg * 100.0f;
89
} else {
90
_motors.set_lateral(0.0f);
91
euler_roll_angle_cd += roll_offset_deg * 100.0f;
92
}
93
euler_roll_angle_cd = wrap_180_cd(euler_roll_angle_cd);
94
}
95
96
/*
97
all other input functions should zero thrust vectoring
98
*/
99
100
// Command euler yaw rate and pitch angle with roll angle specified in body frame
101
// (used only by tailsitter quadplanes)
102
void AC_AttitudeControl_Multi_6DoF::input_euler_rate_yaw_euler_angle_pitch_bf_roll(bool plane_controls, float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_rate_cds) {
103
_motors.set_lateral(0.0f);
104
_motors.set_forward(0.0f);
105
106
AC_AttitudeControl_Multi::input_euler_rate_yaw_euler_angle_pitch_bf_roll(plane_controls, euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_rate_cds);
107
}
108
109
// Command an euler roll, pitch, and yaw rate with angular velocity feedforward and smoothing
110
void AC_AttitudeControl_Multi_6DoF::input_euler_rate_roll_pitch_yaw(float euler_roll_rate_cds, float euler_pitch_rate_cds, float euler_yaw_rate_cds) {
111
_motors.set_lateral(0.0f);
112
_motors.set_forward(0.0f);
113
114
AC_AttitudeControl_Multi::input_euler_rate_roll_pitch_yaw(euler_roll_rate_cds, euler_pitch_rate_cds, euler_yaw_rate_cds);
115
}
116
117
// Command an angular velocity with angular velocity feedforward and smoothing
118
void AC_AttitudeControl_Multi_6DoF::input_rate_bf_roll_pitch_yaw(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) {
119
_motors.set_lateral(0.0f);
120
_motors.set_forward(0.0f);
121
122
AC_AttitudeControl_Multi::input_rate_bf_roll_pitch_yaw(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
123
}
124
125
// Command an angular velocity with angular velocity feedforward and smoothing
126
void AC_AttitudeControl_Multi_6DoF::input_rate_bf_roll_pitch_yaw_2(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) {
127
_motors.set_lateral(0.0f);
128
_motors.set_forward(0.0f);
129
130
AC_AttitudeControl_Multi::input_rate_bf_roll_pitch_yaw_2(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
131
}
132
133
// Command an angular velocity with angular velocity smoothing using rate loops only with integrated rate error stabilization
134
void AC_AttitudeControl_Multi_6DoF::input_rate_bf_roll_pitch_yaw_3(float roll_rate_bf_cds, float pitch_rate_bf_cds, float yaw_rate_bf_cds) {
135
_motors.set_lateral(0.0f);
136
_motors.set_forward(0.0f);
137
138
AC_AttitudeControl_Multi::input_rate_bf_roll_pitch_yaw_3(roll_rate_bf_cds, pitch_rate_bf_cds, yaw_rate_bf_cds);
139
}
140
141
// Command an angular step (i.e change) in body frame angle
142
void AC_AttitudeControl_Multi_6DoF::input_angle_step_bf_roll_pitch_yaw(float roll_angle_step_bf_cd, float pitch_angle_step_bf_cd, float yaw_angle_step_bf_cd) {
143
_motors.set_lateral(0.0f);
144
_motors.set_forward(0.0f);
145
146
AC_AttitudeControl_Multi::input_angle_step_bf_roll_pitch_yaw(roll_angle_step_bf_cd, pitch_angle_step_bf_cd, yaw_angle_step_bf_cd);
147
}
148
149
// Command a Quaternion attitude with feedforward and smoothing
150
// attitude_desired_quat: is updated on each time_step (_dt) by the integral of the angular velocity
151
void AC_AttitudeControl_Multi_6DoF::input_quaternion(Quaternion& attitude_desired_quat, Vector3f ang_vel_body) {
152
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
153
AP_HAL::panic("input_quaternion not implemented AC_AttitudeControl_Multi_6DoF");
154
#endif
155
156
_motors.set_lateral(0.0f);
157
_motors.set_forward(0.0f);
158
159
AC_AttitudeControl_Multi::input_quaternion(attitude_desired_quat, ang_vel_body);
160
}
161
162
163
AC_AttitudeControl_Multi_6DoF *AC_AttitudeControl_Multi_6DoF::_singleton = nullptr;
164
165
#endif // AP_SCRIPTING_ENABLED
166
167