Plane: fixed some warnings

This commit is contained in:
Andrew Tridgell 2014-04-03 12:48:06 +11:00
parent 27ad8c39d6
commit 1efadb7a05
2 changed files with 6 additions and 4 deletions

View File

@ -27,13 +27,13 @@
// Header includes
////////////////////////////////////////////////////////////////////////////////
#include <AP_HAL.h>
#include <math.h>
#include <stdarg.h>
#include <stdio.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_Menu.h>
#include <AP_Param.h>
#include <AP_GPS.h> // ArduPilot GPS library
@ -498,7 +498,9 @@ static struct {
bool locked_course;
float locked_course_err;
} steer_state = {
hold_course_cd : -1,
hold_course_cd : -1,
locked_course : false,
locked_course_err : 0
};

View File

@ -22,10 +22,10 @@ static float get_speed_scaler(void)
speed_scaler = constrain_float(speed_scaler, 0.5, 2.0);
} else {
if (channel_throttle->servo_out > 0) {
speed_scaler = 0.5 + ((float)THROTTLE_CRUISE / channel_throttle->servo_out / 2.0); // First order taylor expansion of square root
speed_scaler = 0.5f + ((float)THROTTLE_CRUISE / channel_throttle->servo_out / 2.0f); // First order taylor expansion of square root
// Should maybe be to the 2/7 power, but we aren't goint to implement that...
}else{
speed_scaler = 1.67;
speed_scaler = 1.67f;
}
// This case is constrained tighter as we don't have real speed info
speed_scaler = constrain_float(speed_scaler, 0.6, 1.67);