forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 26
/
Copy pathtiltrotor.h
137 lines (102 loc) · 3.84 KB
/
tiltrotor.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <AP_Param/AP_Param.h>
#include "transition.h"
class QuadPlane;
class AP_MotorsMulticopter;
class Tiltrotor_Transition;
class Tiltrotor
{
friend class QuadPlane;
friend class Plane;
friend class Tiltrotor_Transition;
public:
Tiltrotor(QuadPlane& _quadplane, AP_MotorsMulticopter*& _motors);
bool enabled() const { return (enable > 0) && setup_complete;}
void setup();
void slew(float tilt);
void binary_slew(bool forward);
void update();
void continuous_update();
void binary_update();
void vectoring();
void bicopter_output();
void tilt_compensate_angle(float *thrust, uint8_t num_motors, float non_tilted_mul, float tilted_mul);
void tilt_compensate(float *thrust, uint8_t num_motors);
bool tilt_over_max_angle(void) const;
bool is_motor_tilting(uint8_t motor) const {
return tilt_mask.get() & (1U<<motor);
}
bool fully_fwd() const;
bool fully_up() const;
float tilt_max_change(bool up, bool in_flap_range = false) const;
float get_fully_forward_tilt() const;
float get_forward_flight_tilt() const;
// update yaw target for tiltrotor transition
void update_yaw_target();
bool is_vectored() const { return enabled() && _is_vectored; }
bool has_fw_motor() const { return _have_fw_motor; }
bool has_vtol_motor() const { return _have_vtol_motor; }
bool motors_active() const { return enabled() && _motors_active; }
// true if the tilts have completed slewing
// always return true if not enabled or not a continuous type
bool tilt_angle_achieved() const { return !enabled() || (type != TILT_TYPE_CONTINUOUS) || angle_achieved; }
AP_Int8 enable;
AP_Int16 tilt_mask;
AP_Int16 max_rate_up_dps;
AP_Int16 max_rate_down_dps;
AP_Int8 max_angle_deg;
AP_Int8 type;
AP_Float tilt_yaw_angle;
AP_Float fixed_angle;
AP_Float fixed_gain;
AP_Float flap_angle_deg;
float current_tilt;
float current_throttle;
bool _motors_active:1;
float transition_yaw_cd;
uint32_t transition_yaw_set_ms;
bool _is_vectored;
// types of tilt mechanisms
enum {TILT_TYPE_CONTINUOUS =0,
TILT_TYPE_BINARY =1,
TILT_TYPE_VECTORED_YAW =2,
TILT_TYPE_BICOPTER =3
};
static const struct AP_Param::GroupInfo var_info[];
private:
bool setup_complete;
// true if a fixed forward motor is setup
bool _have_fw_motor;
// true if all motors tilt with no fixed VTOL motor
bool _have_vtol_motor;
// true if the current tilt angle is equal to the desired
// with slow tilt rates the tilt angle can lag
bool angle_achieved;
// refences for convenience
QuadPlane& quadplane;
AP_MotorsMulticopter*& motors;
Tiltrotor_Transition* transition;
};
// Transition for separate left thrust quadplanes
class Tiltrotor_Transition : public SLT_Transition
{
friend class Tiltrotor;
public:
Tiltrotor_Transition(QuadPlane& _quadplane, AP_MotorsMulticopter*& _motors, Tiltrotor& _tiltrotor):SLT_Transition(_quadplane, _motors), tiltrotor(_tiltrotor) {};
bool update_yaw_target(float& yaw_target_cd) override;
bool show_vtol_view() const override;
private:
Tiltrotor& tiltrotor;
};