diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index 387f2c5406..2eae50f724 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -1314,7 +1314,7 @@ static void Log_Write_Mode(uint8_t mode) { } static void Log_Write_Raw() { } -void print_latlon(BetterStream *s, int32_t lat_or_lon) { +void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon) { } static void Log_Write_GPS() { } diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 607c99a676..9ffffc56c4 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -35,9 +35,9 @@ static int32_t read_barometer(void) static int16_t read_sonar(void) { #if CONFIG_SONAR == ENABLED - int16_t temp_alt = sonar.read(); + int16_t temp_alt = sonar->read(); - if(temp_alt >= sonar.min_distance && temp_alt <= sonar.max_distance * 0.70) { + if(temp_alt >= sonar->min_distance && temp_alt <= sonar->max_distance * 0.70) { sonar_alt_ok = true; }else{ sonar_alt_ok = false; diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index ec620370b4..f3ac9f2bd1 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -292,8 +292,8 @@ init_rate_controllers(); // Experimental AP_Limits library - set constraints, limits, fences, minima, // maxima on various parameters //////////////////////////////////////////////////////////////////////////////// +static void init_ap_limits() { #if AP_LIMITS == ENABLED - // The linked list looks (logically) like this [limits module] -> [first // limit module] -> [second limit module] -> [third limit module] -> NULL