Copter: fixes for AP_HAL merge

This commit is contained in:
Andrew Tridgell 2013-01-02 09:54:32 +11:00
parent 51d987a890
commit 17a63dc76a
3 changed files with 4 additions and 4 deletions

View File

@ -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() {
}

View File

@ -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;

View File

@ -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