Copter: minor formatting fixes

No functional change
This commit is contained in:
Randy Mackay 2016-10-10 12:11:14 +09:00
parent 61fa73f25d
commit 3b6e56d1a0

View File

@ -301,7 +301,8 @@ void Copter::exit_mode(control_mode_t old_control_mode, control_mode_t new_contr
}
// returns true or false whether mode requires GPS
bool Copter::mode_requires_GPS(control_mode_t mode) {
bool Copter::mode_requires_GPS(control_mode_t mode)
{
switch (mode) {
case AUTO:
case GUIDED:
@ -320,7 +321,8 @@ bool Copter::mode_requires_GPS(control_mode_t mode) {
}
// mode_has_manual_throttle - returns true if the flight mode has a manual throttle (i.e. pilot directly controls throttle)
bool Copter::mode_has_manual_throttle(control_mode_t mode) {
bool Copter::mode_has_manual_throttle(control_mode_t mode)
{
switch (mode) {
case ACRO:
case STABILIZE:
@ -332,7 +334,8 @@ bool Copter::mode_has_manual_throttle(control_mode_t mode) {
// mode_allows_arming - returns true if vehicle can be armed in the specified mode
// arming_from_gcs should be set to true if the arming request comes from the ground station
bool Copter::mode_allows_arming(control_mode_t mode, bool arming_from_gcs) {
bool Copter::mode_allows_arming(control_mode_t mode, bool arming_from_gcs)
{
if (mode_has_manual_throttle(mode) || mode == LOITER || mode == ALT_HOLD || mode == POSHOLD || mode == DRIFT || mode == SPORT || mode == THROW || (arming_from_gcs && (mode == GUIDED || mode == GUIDED_NOGPS))) {
return true;
}
@ -340,7 +343,8 @@ bool Copter::mode_allows_arming(control_mode_t mode, bool arming_from_gcs) {
}
// notify_flight_mode - sets notify object based on flight mode. Only used for OreoLED notify device
void Copter::notify_flight_mode(control_mode_t mode) {
void Copter::notify_flight_mode(control_mode_t mode)
{
switch (mode) {
case AUTO:
case GUIDED: