Rover: rename control_mode_from_num to mode_from_mode_num

This commit is contained in:
Randy Mackay 2017-12-12 09:38:40 +09:00
parent 99bafb0df1
commit f6f40afcda
4 changed files with 5 additions and 5 deletions

View File

@ -1470,7 +1470,7 @@ AP_Mission *GCS_MAVLINK_Rover::get_mission()
bool GCS_MAVLINK_Rover::set_mode(const uint8_t mode)
{
Mode *new_mode = rover.control_mode_from_num((enum mode)mode);
Mode *new_mode = rover.mode_from_mode_num((enum mode)mode);
if (new_mode == nullptr) {
return false;
}

View File

@ -454,7 +454,7 @@ private:
void delay(uint32_t ms);
// control_modes.cpp
Mode *control_mode_from_num(enum mode num);
Mode *mode_from_mode_num(enum mode num);
void read_control_switch();
uint8_t readSwitch(void);
void reset_control_switch();

View File

@ -2,7 +2,7 @@
static const int16_t CH_7_PWM_TRIGGER = 1800;
Mode *Rover::control_mode_from_num(const enum mode num)
Mode *Rover::mode_from_mode_num(const enum mode num)
{
Mode *ret = nullptr;
switch (num) {
@ -73,7 +73,7 @@ void Rover::read_control_switch()
return;
}
Mode *new_mode = control_mode_from_num((enum mode)modes[switchPosition].get());
Mode *new_mode = mode_from_mode_num((enum mode)modes[switchPosition].get());
if (new_mode != nullptr) {
set_mode(*new_mode, MODE_REASON_TX_COMMAND);
}

View File

@ -140,7 +140,7 @@ void Rover::init_ardupilot()
startup_ground();
Mode *initial_mode = control_mode_from_num((enum mode)g.initial_mode.get());
Mode *initial_mode = mode_from_mode_num((enum mode)g.initial_mode.get());
if (initial_mode == nullptr) {
initial_mode = &mode_initializing;
}