AP_OSD: correct includes for AP_Arming change
This file was getting the copter-or-heli define from AP_Arming, which was getting it from AP_InertialSensor. This broke when AP_Arming stopped getting AP_InertialSensor, so add the include. Also takes the opportunity to stop including GCS.h
This commit is contained in:
parent
f77d1812b8
commit
d926aa2e11
@ -26,9 +26,9 @@
|
||||
#include <AP_HAL/Util.h>
|
||||
#include <limits.h>
|
||||
#include <ctype.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <AP_RCMapper/AP_RCMapper.h>
|
||||
#include <AP_Arming/AP_Arming.h>
|
||||
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -629,7 +629,7 @@ void AP_OSD_ParamScreen::save_parameters()
|
||||
|
||||
// handle OSD configuration messages
|
||||
#if HAL_GCS_ENABLED
|
||||
void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const GCS_MAVLINK& link)
|
||||
void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& packet, const class GCS_MAVLINK& link)
|
||||
{
|
||||
// request out of range - return an error
|
||||
if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) {
|
||||
@ -642,7 +642,7 @@ void AP_OSD_ParamScreen::handle_write_msg(const mavlink_osd_param_config_t& pack
|
||||
}
|
||||
|
||||
// handle OSD show configuration messages
|
||||
void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t& packet, const GCS_MAVLINK& link)
|
||||
void AP_OSD_ParamScreen::handle_read_msg(const mavlink_osd_param_show_config_t& packet, const class GCS_MAVLINK& link)
|
||||
{
|
||||
// request out of range - return an error
|
||||
if (packet.osd_index < 1 || packet.osd_index > AP_OSD_ParamScreen::NUM_PARAMS) {
|
||||
|
Loading…
Reference in New Issue
Block a user