4 #include <AP_Param/AP_Param.h>
8 class to support "toy" mode for simplified user interaction for
9 large volume consumer vehicles
18 bool enabled(void) const {
19 return enable
.get() != 0;
24 // get throttle mid-point
25 int16_t get_throttle_mid(void) {
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
[];
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 {
54 bool is_f412_buttons(void) const {
60 ACTION_TAKE_PHOTO
= 1,
61 ACTION_TOGGLE_VIDEO
= 2,
63 ACTION_MODE_ALTHOLD
= 4,
65 ACTION_MODE_LOITER
= 6,
67 ACTION_MODE_CIRCLE
= 8,
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,
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
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
105 BLINK_NO_RX
= 0x1111,
106 BLINK_SLOW_1
= 0xF0FF,
107 BLINK_VSLOW
= 0xF000,
108 BLINK_MED_1
= 0xF0F0,
111 bool done_first_update
;
113 AP_Int8 primary_mode
[2];
123 uint32_t power_counter
;
124 uint32_t throttle_low_counter
;
125 uint32_t throttle_high_counter
;
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
;
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
;
170 LOAD_TYPE_CONSTANT
=0,
178 uint8_t filter_counter
;
184 static const struct load_data load_data1
[];