@ -299,7 +299,7 @@ private:
AP_Frsky_Telem frsky_telemetry;
#endif
#if DEVO_TELEM_ENABLED == ENABLED
AP_DEVO_Telem devo_telemetry{ahrs};
AP_DEVO_Telem devo_telemetry;
uint32_t control_sensors_present;
@ -87,7 +87,7 @@ void Rover::init_ardupilot()
frsky_telemetry.init((is_boat() ? MAV_TYPE_SURFACE_BOAT : MAV_TYPE_GROUND_ROVER));
devo_telemetry.init(serial_manager);
devo_telemetry.init();
#if OSD_ENABLED == ENABLED