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/AntennaTracker/mode.h
Views: 1798
1
#pragma once
2
3
#include <stdint.h>
4
#include <AP_Math/AP_Math.h>
5
6
class Mode {
7
public:
8
enum class Number {
9
MANUAL=0,
10
STOP=1,
11
SCAN=2,
12
SERVOTEST=3,
13
GUIDED=4,
14
AUTO=10,
15
INITIALISING=16
16
// Mode number 30 reserved for "offboard" for external/lua control.
17
};
18
19
Mode() {}
20
21
// do not allow copying
22
CLASS_NO_COPY(Mode);
23
24
// returns a unique number specific to this mode
25
virtual Mode::Number number() const = 0;
26
virtual const char* name() const = 0;
27
28
virtual bool requires_armed_servos() const = 0;
29
30
virtual void update() = 0;
31
32
protected:
33
void update_scan();
34
void update_auto();
35
36
bool get_ef_yaw_direction();
37
38
void calc_angle_error(float pitch, float yaw, bool direction_reversed);
39
void convert_ef_to_bf(float pitch, float yaw, float& bf_pitch, float& bf_yaw);
40
bool convert_bf_to_ef(float pitch, float yaw, float& ef_pitch, float& ef_yaw);
41
};
42
43
class ModeAuto : public Mode {
44
public:
45
Mode::Number number() const override { return Mode::Number::AUTO; }
46
const char* name() const override { return "Auto"; }
47
bool requires_armed_servos() const override { return true; }
48
void update() override;
49
};
50
51
class ModeGuided : public Mode {
52
public:
53
Mode::Number number() const override { return Mode::Number::GUIDED; }
54
const char* name() const override { return "Guided"; }
55
bool requires_armed_servos() const override { return true; }
56
void update() override;
57
58
void set_angle(const Quaternion &target_att, bool use_yaw_rate, float yaw_rate_rads) {
59
_target_att = target_att;
60
_use_yaw_rate = use_yaw_rate;
61
_yaw_rate_rads = yaw_rate_rads;
62
}
63
64
private:
65
Quaternion _target_att;
66
bool _use_yaw_rate;
67
float _yaw_rate_rads;
68
};
69
70
class ModeInitialising : public Mode {
71
public:
72
Mode::Number number() const override { return Mode::Number::INITIALISING; }
73
const char* name() const override { return "Initialising"; }
74
bool requires_armed_servos() const override { return false; }
75
void update() override {};
76
};
77
78
class ModeManual : public Mode {
79
public:
80
Mode::Number number() const override { return Mode::Number::MANUAL; }
81
const char* name() const override { return "Manual"; }
82
bool requires_armed_servos() const override { return true; }
83
void update() override;
84
};
85
86
class ModeScan : public Mode {
87
public:
88
Mode::Number number() const override { return Mode::Number::SCAN; }
89
const char* name() const override { return "Scan"; }
90
bool requires_armed_servos() const override { return true; }
91
void update() override;
92
};
93
94
class ModeServoTest : public Mode {
95
public:
96
Mode::Number number() const override { return Mode::Number::SERVOTEST; }
97
const char* name() const override { return "ServoTest"; }
98
bool requires_armed_servos() const override { return true; }
99
void update() override {};
100
101
bool set_servo(uint8_t servo_num, uint16_t pwm);
102
};
103
104
class ModeStop : public Mode {
105
public:
106
Mode::Number number() const override { return Mode::Number::STOP; }
107
const char* name() const override { return "Stop"; }
108
bool requires_armed_servos() const override { return false; }
109
void update() override {};
110
};
111
112