From 17f8b89b17afcd75fde8785ee40024042c504cdc Mon Sep 17 00:00:00 2001 From: TsuyoshiKawamura Date: Tue, 8 Jan 2019 02:22:03 +0900 Subject: [PATCH] Rover: move mode_from_mode_num to mode.cpp --- APMrover2/RC_Channel.cpp | 46 ---------------------------------------- APMrover2/Rover.h | 2 +- APMrover2/mode.cpp | 46 ++++++++++++++++++++++++++++++++++++++++ 3 files changed, 47 insertions(+), 47 deletions(-) diff --git a/APMrover2/RC_Channel.cpp b/APMrover2/RC_Channel.cpp index 52d7c4f352..92cd5af824 100644 --- a/APMrover2/RC_Channel.cpp +++ b/APMrover2/RC_Channel.cpp @@ -10,52 +10,6 @@ #include -Mode *Rover::mode_from_mode_num(const enum Mode::Number num) -{ - Mode *ret = nullptr; - switch (num) { - case Mode::Number::MANUAL: - ret = &mode_manual; - break; - case Mode::Number::ACRO: - ret = &mode_acro; - break; - case Mode::Number::STEERING: - ret = &mode_steering; - break; - case Mode::Number::HOLD: - ret = &mode_hold; - break; - case Mode::Number::LOITER: - ret = &mode_loiter; - break; - case Mode::Number::FOLLOW: - ret = &mode_follow; - break; - case Mode::Number::SIMPLE: - ret = &mode_simple; - break; - case Mode::Number::AUTO: - ret = &mode_auto; - break; - case Mode::Number::RTL: - ret = &mode_rtl; - break; - case Mode::Number::SMART_RTL: - ret = &mode_smartrtl; - break; - case Mode::Number::GUIDED: - ret = &mode_guided; - break; - case Mode::Number::INITIALISING: - ret = &mode_initializing; - break; - default: - break; - } - return ret; -} - int8_t RC_Channels_Rover::flight_mode_channel_number() const { return rover.g.mode_channel; diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 69fc5793d0..4777136eb9 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -408,7 +408,7 @@ private: // compat.cpp void delay(uint32_t ms); - // control_modes.cpp + // mode.cpp Mode *mode_from_mode_num(enum Mode::Number num); // crash_check.cpp diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index fe354db3b3..ef7ba5c2f3 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -550,3 +550,49 @@ void Mode::calc_stopping_location(Location& stopping_loc) location_offset(stopping_loc, stopping_offset.x, stopping_offset.y); } + +Mode *Rover::mode_from_mode_num(const enum Mode::Number num) +{ + Mode *ret = nullptr; + switch (num) { + case Mode::Number::MANUAL: + ret = &mode_manual; + break; + case Mode::Number::ACRO: + ret = &mode_acro; + break; + case Mode::Number::STEERING: + ret = &mode_steering; + break; + case Mode::Number::HOLD: + ret = &mode_hold; + break; + case Mode::Number::LOITER: + ret = &mode_loiter; + break; + case Mode::Number::FOLLOW: + ret = &mode_follow; + break; + case Mode::Number::SIMPLE: + ret = &mode_simple; + break; + case Mode::Number::AUTO: + ret = &mode_auto; + break; + case Mode::Number::RTL: + ret = &mode_rtl; + break; + case Mode::Number::SMART_RTL: + ret = &mode_smartrtl; + break; + case Mode::Number::GUIDED: + ret = &mode_guided; + break; + case Mode::Number::INITIALISING: + ret = &mode_initializing; + break; + default: + break; + } + return ret; +}