Browse Source

Cleanup

sbg
Simon Wilks 12 years ago
parent
commit
715e3e2ebe
  1. 14
      apps/drivers/drv_airspeed.h
  2. 17
      apps/drivers/ets_airspeed/ets_airspeed.cpp
  3. 18
      apps/sensors/sensors.cpp

14
apps/drivers/drv_airspeed.h

@ -46,20 +46,6 @@ @@ -46,20 +46,6 @@
#define AIRSPEED_DEVICE_PATH "/dev/airspeed"
/**
* Airspeed report structure. Reads from the device must be in multiples of this
* structure.
*/
//struct airspeed_report {
// uint64_t timestamp;
// uint8_t diff_pressure; /** differential pressure in Pa */
//};
/*
* ObjDev tag for raw range finder data.
*/
//ORB_DECLARE(sensor_differential_pressure);
/*
* ioctl() definitions
*

17
apps/drivers/ets_airspeed/ets_airspeed.cpp

@ -74,20 +74,22 @@ @@ -74,20 +74,22 @@
#include <uORB/topics/subsystem_info.h>
/* Configuration Constants */
#define I2C_BUS PX4_I2C_BUS_ESC
#define I2C_BUS PX4_I2C_BUS_ESC // XXX Replace with PX4_I2C_BUS_EXPANSION before submitting.
#define I2C_ADDRESS 0x75
/* ETS_AIRSPEED Registers addresses */
#define READ_CMD 0x07 /* Read the data */
/* Max measurement rate is 100Hz */
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
/* The Eagle Tree Airspeed V3 can only provide accurate readings
for speeds from 15km/h upwards. */
/**
* The Eagle Tree Airspeed V3 can only provide accurate readings
* for speeds from 15km/h upwards.
*/
#define MIN_ACCURATE_DIFF_PRES_PA 12
/* oddly, ERROR is not defined for c++ */
/* Oddly, ERROR is not defined for C++ */
#ifdef ERROR
# undef ERROR
#endif
@ -109,8 +111,8 @@ public: @@ -109,8 +111,8 @@ public:
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
/**
* Diagnostics - print some basic information about the driver.
*/
* Diagnostics - print some basic information about the driver.
*/
void print_info();
protected:
@ -163,6 +165,7 @@ private: @@ -163,6 +165,7 @@ private:
void cycle();
int measure();
int collect();
/**
* Static trampoline from the workq context; because we don't have a
* generic workq wrapper yet.

18
apps/sensors/sensors.cpp

@ -99,6 +99,12 @@ @@ -99,6 +99,12 @@
#define BAT_VOL_LOWPASS_2 0.01f
#define VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS 3.5f
/**
* HACK - true temperature is much less than indicated temperature in baro,
* subtract 5 degrees in an attempt to account for the electrical upheating of the PCB
*/
#define PCB_TEMP_ESTIMATE_DEG 5.0f
#define PPM_INPUT_TIMEOUT_INTERVAL 50000 /**< 50 ms timeout / 20 Hz */
#define limit_minus_one_to_one(arg) (arg < -1.0f) ? -1.0f : ((arg > 1.0f) ? 1.0f : arg)
@ -913,15 +919,9 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw) @@ -913,15 +919,9 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
raw.differential_pressure_pa = _diff_pres.differential_pressure_pa;
raw.differential_pressure_counter++;
float airspeed_true = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f,
raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - 5.0f); //factor 1e2 for conversion from mBar to Pa
// XXX HACK - true temperature is much less than indicated temperature in baro,
// subtract 5 degrees in an attempt to account for the electrical upheating of the PCB
float airspeed_indicated = calc_indicated_airspeed(_diff_pres.differential_pressure_pa);
_airspeed.indicated_airspeed_m_s = airspeed_indicated;
_airspeed.true_airspeed_m_s = airspeed_true;
_airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_pa);
_airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f,
raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
/* announce the airspeed if needed, just publish else */
if (_airspeed_pub > 0) {

Loading…
Cancel
Save