diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 2eb0b1c8f7..e1b8988410 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -29,7 +29,7 @@ MAV_TYPE GCS_MAVLINK_Copter::frame_type() const MAV_MODE GCS_MAVLINK_Copter::base_mode() const { - uint8_t base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED; + uint8_t _base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED; // work out the base_mode. This value is not very useful // for APM, but we calculate it as best we can so a generic // MAVLink enabled ground station can work out something about @@ -49,7 +49,7 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const case POSHOLD: case BRAKE: case SMART_RTL: - base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; + _base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED; // note that MAV_MODE_FLAG_AUTO_ENABLED does not match what // APM does in any mode, as that is defined as "system finds its own goal // positions", which APM does not currently do @@ -60,21 +60,21 @@ MAV_MODE GCS_MAVLINK_Copter::base_mode() const // all modes except INITIALISING have some form of manual // override if stick mixing is enabled - base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; + _base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; #if HIL_MODE != HIL_MODE_DISABLED - base_mode |= MAV_MODE_FLAG_HIL_ENABLED; + _base_mode |= MAV_MODE_FLAG_HIL_ENABLED; #endif // we are armed if we are not initialising if (copter.motors != nullptr && copter.motors->armed()) { - base_mode |= MAV_MODE_FLAG_SAFETY_ARMED; + _base_mode |= MAV_MODE_FLAG_SAFETY_ARMED; } // indicate we have set a custom mode - base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; + _base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; - return (MAV_MODE)base_mode; + return (MAV_MODE)_base_mode; } uint32_t GCS_MAVLINK_Copter::custom_mode() const