mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
added altitude to circle mission
This commit is contained in:
parent
0ba8a9f30b
commit
88b3708dcf
@ -318,7 +318,7 @@ public:
|
|||||||
optflow_enabled (OPTFLOW, k_param_optflow_enabled, PSTR("FLOW_ENABLE")),
|
optflow_enabled (OPTFLOW, k_param_optflow_enabled, PSTR("FLOW_ENABLE")),
|
||||||
input_voltage (INPUT_VOLTAGE, k_param_input_voltage, PSTR("IN_VOLT")),
|
input_voltage (INPUT_VOLTAGE, k_param_input_voltage, PSTR("IN_VOLT")),
|
||||||
low_voltage (LOW_VOLTAGE, k_param_low_voltage, PSTR("LOW_VOLT")),
|
low_voltage (LOW_VOLTAGE, k_param_low_voltage, PSTR("LOW_VOLT")),
|
||||||
reset_simple (RESET_SIMPLE, k_param_reset_simple, PSTR("RST_SIMPL")),
|
reset_simple (RESET_SIMPLE, k_param_reset_simple, PSTR("RST_SIMPLE")),
|
||||||
|
|
||||||
waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")),
|
waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")),
|
||||||
command_total (0, k_param_command_total, PSTR("WP_TOTAL")),
|
command_total (0, k_param_command_total, PSTR("WP_TOTAL")),
|
||||||
|
@ -23,7 +23,7 @@ QGC WPL 110
|
|||||||
|
|
||||||
# MAV_CMD_NAV_LOITER_TURNS
|
# MAV_CMD_NAV_LOITER_TURNS
|
||||||
# Turns lat lon alt continue
|
# Turns lat lon alt continue
|
||||||
6 0 3 18 2 0 0 0 0 0 0 1
|
6 0 3 18 2 0 0 0 0 0 20 1
|
||||||
|
|
||||||
# MAV_CMD_DO_SET_ROI, MAV_ROI_WPNEXT = 1
|
# MAV_CMD_DO_SET_ROI, MAV_ROI_WPNEXT = 1
|
||||||
# MAV_ROI WP index ROI index lat lon alt continue
|
# MAV_ROI WP index ROI index lat lon alt continue
|
||||||
|
Loading…
Reference in New Issue
Block a user