15 return enable.get() != 0;
33 static const struct AP_Param::GroupInfo
var_info[];
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);
43 void thrust_limiting(
float *thrust, uint8_t num_motors);
44 void arm_check_compass(
void);
47 bool is_v2450_buttons(
void)
const {
50 bool is_f412_buttons(
void)
const {
56 ACTION_TAKE_PHOTO = 1,
57 ACTION_TOGGLE_VIDEO = 2,
59 ACTION_MODE_ALTHOLD = 4,
61 ACTION_MODE_LOITER = 6,
63 ACTION_MODE_CIRCLE = 8,
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,
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,
82 enum toy_action last_action;
86 FLAG_THR_DISARM = 1<<0,
88 FLAG_UPGRADE_LOITER = 1<<2,
89 FLAG_RTL_CANCEL = 1<<3,
101 BLINK_NO_RX = 0x1111,
102 BLINK_SLOW_1 = 0xF0FF,
103 BLINK_VSLOW = 0xF000,
104 BLINK_MED_1 = 0xF0F0,
107 bool done_first_update;
109 AP_Int8 primary_mode[2];
119 uint32_t power_counter;
120 uint32_t throttle_low_counter;
121 uint32_t throttle_high_counter;
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;
135 uint32_t last_video_ms;
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;
154 float filtered_voltage = 4.0;
156 uint8_t motor_log_counter;
166 LOAD_TYPE_CONSTANT=0,
180 static const struct load_data load_data1[];
static const struct AP_Param::GroupInfo var_info[]
Definition: toy_mode.h:33
control_mode_t
Definition: defines.h:91
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
uint16_t chan[4]
Definition: toy_mode.h:116
AP_Int8 load_filter
Definition: toy_mode.h:176
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
void throttle_adjust(float &throttle_control)
void handle_message(mavlink_message_t *msg)