mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: fixup auto options
This commit is contained in:
parent
50dfe3f197
commit
8b3cc0b255
@ -979,8 +979,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
#if MODE_AUTO_ENABLED == ENABLED
|
#if MODE_AUTO_ENABLED == ENABLED
|
||||||
// @Param: AUTO_OPTIONS
|
// @Param: AUTO_OPTIONS
|
||||||
// @DisplayName: Auto mode options
|
// @DisplayName: Auto mode options
|
||||||
// @Description: A range of options that can be applied to change auto mode behaviour. Allow arming allows the copter to be armed while in auto. Allow taking off without throttle to takeoff allows the copter to takeoff without having to raise the throttle.
|
// @Description: A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle
|
||||||
// @Bitmask: 0:Allow arming,1:Allow taking off without throttle
|
// @Bitmask: 0:Allow Arming,1:Allow Takeoff Without Raising Throttle
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("AUTO_OPTIONS", 40, ParametersG2, auto_options, 0),
|
AP_GROUPINFO("AUTO_OPTIONS", 40, ParametersG2, auto_options, 0),
|
||||||
#endif
|
#endif
|
||||||
|
@ -406,8 +406,8 @@ protected:
|
|||||||
private:
|
private:
|
||||||
|
|
||||||
enum class Options : int32_t {
|
enum class Options : int32_t {
|
||||||
AllowArming = (1 << 0U),
|
AllowArming = (1 << 0U),
|
||||||
BypassThrottle = (1 << 1U),
|
AllowTakeOffWithoutRaisingThrottle = (1 << 1U),
|
||||||
};
|
};
|
||||||
|
|
||||||
bool start_command(const AP_Mission::Mission_Command& cmd);
|
bool start_command(const AP_Mission::Mission_Command& cmd);
|
||||||
@ -521,7 +521,7 @@ private:
|
|||||||
float descend_max; // centimetres
|
float descend_max; // centimetres
|
||||||
} nav_payload_place;
|
} nav_payload_place;
|
||||||
|
|
||||||
bool waiting_for_origin;
|
bool waiting_for_origin; // true if waiting for origin before starting mission
|
||||||
};
|
};
|
||||||
|
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
|
@ -53,10 +53,6 @@ bool ModeAuto::init(bool ignore_checks)
|
|||||||
waiting_for_origin = true;
|
waiting_for_origin = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if the user doesn't want to raise the throttle we can set it automatically
|
|
||||||
if ((copter.g2.auto_options & (int32_t)Options::BypassThrottle) != 0) {
|
|
||||||
copter.set_auto_armed(true);
|
|
||||||
}
|
|
||||||
return true;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
return false;
|
return false;
|
||||||
@ -742,7 +738,7 @@ void ModeAuto::takeoff_run()
|
|||||||
{
|
{
|
||||||
// if the user doesn't want to raise the throttle we can set it automatically
|
// if the user doesn't want to raise the throttle we can set it automatically
|
||||||
// note that this can defeat the disarm check on takeoff
|
// note that this can defeat the disarm check on takeoff
|
||||||
if ((copter.g2.auto_options & (int32_t)Options::BypassThrottle) != 0) {
|
if ((copter.g2.auto_options & (int32_t)Options::AllowTakeOffWithoutRaisingThrottle) != 0) {
|
||||||
copter.set_auto_armed(true);
|
copter.set_auto_armed(true);
|
||||||
}
|
}
|
||||||
auto_takeoff_run();
|
auto_takeoff_run();
|
||||||
|
Loading…
Reference in New Issue
Block a user