Browse Source

Rover: rename control_mode_from_num to mode_from_mode_num

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
f6f40afcda
  1. 2
      APMrover2/GCS_Mavlink.cpp
  2. 2
      APMrover2/Rover.h
  3. 4
      APMrover2/control_modes.cpp
  4. 2
      APMrover2/system.cpp

2
APMrover2/GCS_Mavlink.cpp

@ -1470,7 +1470,7 @@ AP_Mission *GCS_MAVLINK_Rover::get_mission() @@ -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;
}

2
APMrover2/Rover.h

@ -454,7 +454,7 @@ private: @@ -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();

4
APMrover2/control_modes.cpp

@ -2,7 +2,7 @@ @@ -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() @@ -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);
}

2
APMrover2/system.cpp

@ -140,7 +140,7 @@ void Rover::init_ardupilot() @@ -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;
}

Loading…
Cancel
Save