Eagletree Airspeed sensor V3 on PX4IO

Hi,

has anyone the Eagletree airspeed sensor successfully tested on Arduplane FW 3.0.x ?

I’ve tested my setup within the 2.78b FW and the AS is working. After upgrading to ArduPlane FW 3.0.x the sensor values are very low (0.1-0.2) when im blowing into the pilot tube.

This are the params for FW 2.78b:
ARSPD_AUTOCAL 1
ARSPD_ENABLE 1
ARSPD_FBW_MAX 22
ARSPD_FBW_MIN 6
ARSPD_OFFSET 1654,805
ARSPD_PIN 65
ARSPD_RATIO 2
ARSPD_USE 0

Regards
Hxxnrx

Is this on a Pixhawk?
What do you have the ARSPD_TUBE_ORDER set to?
Cheers, Tridge

Hi Tridge,

nop, it’s a PX4FMU+IO.

For the ARSPD_TUBE_ORDER I’ve used the default value 2 and tested 0 an 1also.

Regards
Hxxnrx

Hi Tridge,

I think I’ve found the issue. On the APM side the raw pressure is used (‘ardupilot/libraries/AP_Airspeed/AP_Airspeed_PX4.cpp’):

// read the airspeed sensor
bool AP_Airspeed_PX4::get_differential_pressure(float &pressure)
{
    if (_fd == -1) {
        return false;
    }

    // read from the PX4 airspeed sensor
    float psum = 0;
    float tsum = 0;
    uint16_t count = 0;
    struct differential_pressure_s report;
    
    while (::read(_fd, &report, sizeof(report)) == sizeof(report) &&
           report.timestamp != _last_timestamp) {
        psum += report.differential_pressure_raw_pa;
        tsum += report.temperature;
        count++;
        _last_timestamp = report.timestamp;
    }
    if (count == 0) {
        return false;
    }
    pressure = psum / count;
    _temperature = tsum / count;
    return true;
}

But on the PX4 firmware side the raw pressure isn’t populated (‘PX4Firmware/src/drivers/ets_airspeed/ets_airspeed.cpp’):

int
ETSAirspeed::collect()
{
	int	ret = -EIO;

	/* read from the sensor */
	uint8_t val[2] = {0, 0};

	perf_begin(_sample_perf);

	ret = transfer(nullptr, 0, &val[0], 2);

	if (ret < 0) {
		perf_count(_comms_errors);
		return ret;
	}

	uint16_t diff_pres_pa = val[1] << 8 | val[0];
        if (diff_pres_pa == 0) {
		// a zero value means the pressure sensor cannot give us a
		// value. We need to return, and not report a value or the
		// caller could end up using this value as part of an
		// average
		perf_count(_comms_errors);
		log("zero value from sensor"); 
		return -1;
        }

	if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
		diff_pres_pa = 0;
	} else {
		diff_pres_pa -= _diff_pres_offset;
	}

	// Track maximum differential pressure measured (so we can work out top speed).
	if (diff_pres_pa > _max_differential_pressure_pa) {
		_max_differential_pressure_pa = diff_pres_pa;
	}

	// XXX we may want to smooth out the readings to remove noise.
	differential_pressure_s report;
	report.timestamp = hrt_absolute_time();
	report.error_count = perf_event_count(_comms_errors);
	report.differential_pressure_pa = (float)diff_pres_pa;
	report.voltage = 0;
	report.max_differential_pressure_pa = _max_differential_pressure_pa;

	if (_airspeed_pub > 0 && !(_pub_blocked)) {
		/* publish it */
		orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report);
	}

	new_report(report);

	/* notify anyone waiting for data */
	poll_notify(POLLIN);

	ret = OK;

	perf_end(_sample_perf);

	return ret;
}

Hi Tridge,

find attached a patch which solves the issue. I’ve tested it with version 3.0.0. But it should work also for newer versions.

Regards
Hxxnrx

thanks for the fix! I’ve pushed it to master.
My apologies that I didn’t notice this fix for the 3.0.3 release. It is in the ‘latest’ builds now (or will be in an hours time) and will be in the next stable release.
Cheers, Tridge