AP_Airspeed: fixed some warnings

This commit is contained in:
Andrew Tridgell 2013-09-30 20:46:02 +10:00
parent eef693f243
commit e60d5d4f33
2 changed files with 2 additions and 3 deletions

View File

@ -136,7 +136,6 @@ void AP_Airspeed::calibrate()
{
float sum = 0;
uint8_t count = 0;
uint8_t c;
if (!_enable) {
return;
}

View File

@ -42,9 +42,9 @@ public:
// constructor
AP_Airspeed(const AP_Vehicle::FixedWing &parms) :
_EAS2TAS(1.0f),
_healthy(false),
_calibration(parms),
analog(_pin),
_healthy(false)
analog(_pin)
{
AP_Param::setup_object_defaults(this, var_info);
};