Rover: rename auto_throttle to allows_arming_from_transmitter

This method is only used to determine whether we can arm from the transmitter so better to make its purpose more clear
Also minor comment fix to is_autopilot_mode method
This commit is contained in:
Randy Mackay 2018-01-11 10:54:40 +09:00
parent a190d62813
commit 7dd69f8796
2 changed files with 5 additions and 5 deletions

View File

@ -39,11 +39,11 @@ public:
// attributes of the mode
//
// return if in non-manual mode : AUTO, GUIDED, RTL
// return if in non-manual mode : Auto, Guided, RTL, SmartRTL
virtual bool is_autopilot_mode() const { return false; }
// returns true if the throttle is controlled automatically
virtual bool auto_throttle() { return is_autopilot_mode(); }
// returns true if vehicle can be armed or disarmed from the transmitter in this mode
virtual bool allows_arming_from_transmitter() { return !is_autopilot_mode(); }
//
// attributes for mavlink system status reporting

View File

@ -52,8 +52,8 @@ void Rover::rudder_arm_disarm_check()
return;
}
// if not in a manual throttle mode then disallow rudder arming/disarming
if (control_mode->auto_throttle()) {
// check if arming/disarming allowed from this mode
if (!control_mode->allows_arming_from_transmitter()) {
rudder_arm_timer = 0;
return;
}