AP_Scripting: ahrs/ekf origin script promoted to an applet
[ardupilot.git] / ArduCopter / toy_mode.h
blob13bb12454f9f68544f9469a87d16d63355a674ca
1 #pragma once
3 #include <stdint.h>
4 #include <AP_Param/AP_Param.h>
5 #include "mode.h"
7 /*
8 class to support "toy" mode for simplified user interaction for
9 large volume consumer vehicles
12 class ToyMode
14 public:
15 friend class Copter;
17 ToyMode();
18 bool enabled(void) const {
19 return enable.get() != 0;
22 void update(void);
24 // get throttle mid-point
25 int16_t get_throttle_mid(void) {
26 return throttle_mid;
29 // adjust throttle for throttle takeoff
30 void throttle_adjust(float &throttle_control);
32 // handle mavlink message
33 void handle_message(const mavlink_message_t &msg);
35 void load_test_run(void);
37 static const struct AP_Param::GroupInfo var_info[];
39 private:
41 void trim_update(void);
42 void action_arm(void);
43 void blink_update(void);
44 void send_named_int(const char *name, int32_t value);
45 bool set_and_remember_mode(Mode::Number mode, ModeReason reason);
47 void thrust_limiting(float *thrust, uint8_t num_motors);
48 void arm_check_compass(void);
50 // work out type of button setup
51 bool is_v2450_buttons(void) const {
52 return enable == 1;
54 bool is_f412_buttons(void) const {
55 return enable == 2;
58 enum toy_action {
59 ACTION_NONE = 0,
60 ACTION_TAKE_PHOTO = 1,
61 ACTION_TOGGLE_VIDEO = 2,
62 ACTION_MODE_ACRO = 3,
63 ACTION_MODE_ALTHOLD = 4,
64 ACTION_MODE_AUTO = 5,
65 ACTION_MODE_LOITER = 6,
66 ACTION_MODE_RTL = 7,
67 ACTION_MODE_CIRCLE = 8,
68 ACTION_MODE_LAND = 9,
69 ACTION_MODE_DRIFT = 10,
70 ACTION_MODE_SPORT = 11,
71 ACTION_MODE_AUTOTUNE= 12,
72 ACTION_MODE_POSHOLD = 13,
73 ACTION_MODE_BRAKE = 14,
74 ACTION_MODE_THROW = 15,
75 ACTION_MODE_FLIP = 16,
76 ACTION_MODE_STAB = 17,
77 ACTION_DISARM = 18,
78 ACTION_TOGGLE_MODE = 19,
79 ACTION_ARM_LAND_RTL = 20,
80 ACTION_TOGGLE_SIMPLE = 21,
81 ACTION_TOGGLE_SSIMPLE = 22,
82 ACTION_LOAD_TEST = 23,
83 ACTION_MODE_FLOW = 24,
86 enum toy_action last_action;
88 // these are bitmask indexes for TMODE_FLAGS
89 enum toy_flags {
90 FLAG_THR_DISARM = 1<<0, // disarm on low throttle
91 FLAG_THR_ARM = 1<<1, // arm on high throttle
92 FLAG_UPGRADE_LOITER = 1<<2, // auto upgrade from ALT_HOLD to LOITER
93 FLAG_RTL_CANCEL = 1<<3, // cancel RTL on large stick input
96 enum blink_patterns {
97 BLINK_FULL = 0xFFFF,
98 BLINK_OFF = 0x0000,
99 BLINK_1 = 0xBFFF,
100 BLINK_2 = 0xAFFF,
101 BLINK_3 = 0xABFF,
102 BLINK_4 = 0xAAFF,
103 BLINK_6 = 0xAAAF,
104 BLINK_8 = 0xAAAA,
105 BLINK_NO_RX = 0x1111,
106 BLINK_SLOW_1 = 0xF0FF,
107 BLINK_VSLOW = 0xF000,
108 BLINK_MED_1 = 0xF0F0,
111 bool done_first_update;
112 AP_Int8 enable;
113 AP_Int8 primary_mode[2];
114 AP_Int8 actions[9];
115 AP_Int8 trim_auto;
116 AP_Int16 flags;
118 struct {
119 uint32_t start_ms;
120 uint16_t chan[4];
121 } trim;
123 uint32_t power_counter;
124 uint32_t throttle_low_counter;
125 uint32_t throttle_high_counter;
126 uint16_t last_ch5;
127 bool last_left_button;
128 uint8_t last_mode_choice;
129 int32_t left_press_counter;
130 int32_t right_press_counter;
131 bool ignore_left_change;
132 int16_t throttle_mid = 500;
133 uint32_t throttle_arm_ms;
134 bool upgrade_to_loiter;
135 uint32_t last_action_ms;
136 uint32_t reset_turtle_start_ms;
138 // time when we were last told we are recording video
139 uint32_t last_video_ms;
141 // current blink indexes
142 uint16_t red_blink_pattern;
143 uint16_t green_blink_pattern;
144 uint8_t red_blink_index;
145 uint8_t green_blink_index;
146 uint16_t red_blink_count;
147 uint16_t green_blink_count;
148 uint8_t blink_disarm;
150 struct {
151 AP_Float volt_min;
152 AP_Float volt_max;
153 AP_Float thrust_min;
154 AP_Float thrust_max;
155 } filter;
157 // low-pass voltage
158 float filtered_voltage = 4.0;
160 uint8_t motor_log_counter;
162 // remember the last mode we set
163 Mode::Number last_set_mode = Mode::Number::LOITER;
165 struct load_data {
166 uint16_t m[4];
169 enum load_type {
170 LOAD_TYPE_CONSTANT=0,
171 LOAD_TYPE_LOG1=1,
172 LOAD_TYPE_LOG2=2,
175 struct {
176 bool running;
177 uint32_t row;
178 uint8_t filter_counter;
179 AP_Float load_mul;
180 AP_Int8 load_filter;
181 AP_Int8 load_type;
182 } load_test;
184 static const struct load_data load_data1[];