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