diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index d0dd641dea..a270cf96fc 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -369,7 +369,7 @@ const AP_Param::Info Rover::var_info[] = { // @Path: Parameters.cpp GOBJECT(g2, "", ParametersG2), -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED || OSD_PARAM_ENABLED // @Group: OSD // @Path: ../libraries/AP_OSD/AP_OSD.cpp GOBJECT(osd, "OSD", AP_OSD), diff --git a/Rover/Rover.h b/Rover/Rover.h index aa487edbef..97daa488b6 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -165,7 +165,7 @@ private: OpticalFlow optflow; #endif -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED || OSD_PARAM_ENABLED AP_OSD osd; #endif @@ -390,7 +390,7 @@ private: bool should_log(uint32_t mask); bool is_boat() const; -#if OSD_ENABLED == ENABLED +#if OSD_ENABLED || OSD_PARAM_ENABLED void publish_osd_info(); #endif