aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:13:11 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-04-22 11:13:11 +0200
commit302233a34f23a57b67d4ebb8ba3e553ad9d8c445 (patch)
tree9fa902073c358151e1ca27430e00919048006d76 /src/drivers
parentdfd9601b571057e73668d9b39d584bc4eb9cc305 (diff)
parentf0e28a60ca216ec147b359eef5500f190f192c82 (diff)
downloadpx4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.tar.gz
px4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.tar.bz2
px4-firmware-302233a34f23a57b67d4ebb8ba3e553ad9d8c445.zip
Merge branch 'master' into mpc_local_pos
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/blinkm/blinkm.cpp141
-rw-r--r--src/drivers/drv_range_finder.h11
-rw-r--r--src/drivers/gps/gps.cpp4
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp128
-rw-r--r--src/drivers/px4io/px4io.cpp24
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp9
-rw-r--r--src/drivers/sf0x/sf0x.cpp12
-rw-r--r--src/drivers/stm32/adc/adc.cpp47
8 files changed, 304 insertions, 72 deletions
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index 2361f4dd1..b75c2297f 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -48,11 +48,14 @@
* The recognized number off cells, will be blinked 5 times in purple color.
* 2 Cells = 2 blinks
* ...
- * 5 Cells = 5 blinks
+ * 6 Cells = 6 blinks
* Now the Application will show the actual selected Flightmode, GPS-Fix and Battery Warnings and Alerts.
*
- * System disarmed:
- * The BlinkM should lit solid red.
+ * System disarmed and safe:
+ * The BlinkM should light solid cyan.
+ *
+ * System safety off but not armed:
+ * The BlinkM should light flashing orange
*
* System armed:
* One message is made of 4 Blinks and a pause in the same length as the 4 blinks.
@@ -67,10 +70,10 @@
* (X = on, _=off)
*
* The first 3 blinks indicates the status of the GPS-Signal (red):
- * 0-4 satellites = X-X-X-X-_-_-_-_-_-_-
- * 5 satellites = X-X-_-X-_-_-_-_-_-_-
- * 6 satellites = X-_-_-X-_-_-_-_-_-_-
- * >=7 satellites = _-_-_-X-_-_-_-_-_-_-
+ * 0-4 satellites = X-X-X-X-X-_-_-_-_-_-
+ * 5 satellites = X-X-_-X-X-_-_-_-_-_-
+ * 6 satellites = X-_-_-X-X-_-_-_-_-_-
+ * >=7 satellites = _-_-_-X-X-_-_-_-_-_-
* If no GPS is found the first 3 blinks are white
*
* The fourth Blink indicates the Flightmode:
@@ -119,6 +122,7 @@
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/safety.h>
static const float MAX_CELL_VOLTAGE = 4.3f;
static const int LED_ONTIME = 120;
@@ -166,10 +170,12 @@ private:
enum ledColors {
LED_OFF,
LED_RED,
+ LED_ORANGE,
LED_YELLOW,
LED_PURPLE,
LED_GREEN,
LED_BLUE,
+ LED_CYAN,
LED_WHITE,
LED_AMBER
};
@@ -380,6 +386,7 @@ BlinkM::led()
static int vehicle_control_mode_sub_fd;
static int vehicle_gps_position_sub_fd;
static int actuator_armed_sub_fd;
+ static int safety_sub_fd;
static int num_of_cells = 0;
static int detected_cells_runcount = 0;
@@ -402,16 +409,20 @@ BlinkM::led()
if(!topic_initialized) {
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
- orb_set_interval(vehicle_status_sub_fd, 1000);
+ orb_set_interval(vehicle_status_sub_fd, 250);
vehicle_control_mode_sub_fd = orb_subscribe(ORB_ID(vehicle_control_mode));
- orb_set_interval(vehicle_control_mode_sub_fd, 1000);
+ orb_set_interval(vehicle_control_mode_sub_fd, 250);
actuator_armed_sub_fd = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(actuator_armed_sub_fd, 1000);
+ orb_set_interval(actuator_armed_sub_fd, 250);
vehicle_gps_position_sub_fd = orb_subscribe(ORB_ID(vehicle_gps_position));
- orb_set_interval(vehicle_gps_position_sub_fd, 1000);
+ orb_set_interval(vehicle_gps_position_sub_fd, 250);
+
+ /* Subscribe to safety topic */
+ safety_sub_fd = orb_subscribe(ORB_ID(safety));
+ orb_set_interval(safety_sub_fd, 250);
topic_initialized = true;
}
@@ -433,7 +444,9 @@ BlinkM::led()
if(num_of_cells > 4) {
t_led_color[4] = LED_PURPLE;
}
- t_led_color[5] = LED_OFF;
+ if(num_of_cells > 5) {
+ t_led_color[5] = LED_PURPLE;
+ }
t_led_color[6] = LED_OFF;
t_led_color[7] = LED_OFF;
t_led_blink = LED_BLINK;
@@ -467,14 +480,17 @@ BlinkM::led()
struct vehicle_control_mode_s vehicle_control_mode;
struct actuator_armed_s actuator_armed;
struct vehicle_gps_position_s vehicle_gps_position_raw;
+ struct safety_s safety;
memset(&vehicle_status_raw, 0, sizeof(vehicle_status_raw));
memset(&vehicle_gps_position_raw, 0, sizeof(vehicle_gps_position_raw));
+ memset(&safety, 0, sizeof(safety));
bool new_data_vehicle_status;
bool new_data_vehicle_control_mode;
bool new_data_actuator_armed;
bool new_data_vehicle_gps_position;
+ bool new_data_safety;
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
@@ -520,7 +536,12 @@ BlinkM::led()
no_data_vehicle_gps_position = 3;
}
+ /* update safety topic */
+ orb_check(safety_sub_fd, &new_data_safety);
+ if (new_data_safety) {
+ orb_copy(ORB_ID(safety), safety_sub_fd, &safety);
+ }
/* get number of used satellites in navigation */
num_of_used_sats = 0;
@@ -541,19 +562,7 @@ BlinkM::led()
printf("<blinkm> cells found:%d\n", num_of_cells);
} else {
- if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
- /* LED Pattern for battery low warning */
- led_color_1 = LED_YELLOW;
- led_color_2 = LED_YELLOW;
- led_color_3 = LED_YELLOW;
- led_color_4 = LED_YELLOW;
- led_color_5 = LED_YELLOW;
- led_color_6 = LED_YELLOW;
- led_color_7 = LED_YELLOW;
- led_color_8 = LED_YELLOW;
- led_blink = LED_BLINK;
-
- } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
+ if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) {
/* LED Pattern for battery critical alerting */
led_color_1 = LED_RED;
led_color_2 = LED_RED;
@@ -565,21 +574,56 @@ BlinkM::led()
led_color_8 = LED_RED;
led_blink = LED_BLINK;
+ } else if(vehicle_status_raw.rc_signal_lost) {
+ /* LED Pattern for FAILSAFE */
+ led_color_1 = LED_BLUE;
+ led_color_2 = LED_BLUE;
+ led_color_3 = LED_BLUE;
+ led_color_4 = LED_BLUE;
+ led_color_5 = LED_BLUE;
+ led_color_6 = LED_BLUE;
+ led_color_7 = LED_BLUE;
+ led_color_8 = LED_BLUE;
+ led_blink = LED_BLINK;
+
+ } else if(vehicle_status_raw.battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
+ /* LED Pattern for battery low warning */
+ led_color_1 = LED_YELLOW;
+ led_color_2 = LED_YELLOW;
+ led_color_3 = LED_YELLOW;
+ led_color_4 = LED_YELLOW;
+ led_color_5 = LED_YELLOW;
+ led_color_6 = LED_YELLOW;
+ led_color_7 = LED_YELLOW;
+ led_color_8 = LED_YELLOW;
+ led_blink = LED_BLINK;
+
} else {
/* no battery warnings here */
if(actuator_armed.armed == false) {
/* system not armed */
- led_color_1 = LED_RED;
- led_color_2 = LED_RED;
- led_color_3 = LED_RED;
- led_color_4 = LED_RED;
- led_color_5 = LED_RED;
- led_color_6 = LED_RED;
- led_color_7 = LED_RED;
- led_color_8 = LED_RED;
- led_blink = LED_NOBLINK;
-
+ if(safety.safety_off){
+ led_color_1 = LED_ORANGE;
+ led_color_2 = LED_ORANGE;
+ led_color_3 = LED_ORANGE;
+ led_color_4 = LED_ORANGE;
+ led_color_5 = LED_ORANGE;
+ led_color_6 = LED_ORANGE;
+ led_color_7 = LED_ORANGE;
+ led_color_8 = LED_ORANGE;
+ led_blink = LED_BLINK;
+ }else{
+ led_color_1 = LED_CYAN;
+ led_color_2 = LED_CYAN;
+ led_color_3 = LED_CYAN;
+ led_color_4 = LED_CYAN;
+ led_color_5 = LED_CYAN;
+ led_color_6 = LED_CYAN;
+ led_color_7 = LED_CYAN;
+ led_color_8 = LED_CYAN;
+ led_blink = LED_NOBLINK;
+ }
} else {
/* armed system - initial led pattern */
led_color_1 = LED_RED;
@@ -593,23 +637,22 @@ BlinkM::led()
led_blink = LED_BLINK;
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
-
- //XXX please check
- if (vehicle_control_mode.flag_control_position_enabled)
+ /* indicate main control state */
+ if (vehicle_status_raw.main_state == MAIN_STATE_EASY)
led_color_4 = LED_GREEN;
- else if (vehicle_control_mode.flag_control_velocity_enabled)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
led_color_4 = LED_BLUE;
- else if (vehicle_control_mode.flag_control_attitude_enabled)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_SEATBELT)
led_color_4 = LED_YELLOW;
- else if (vehicle_control_mode.flag_control_manual_enabled)
- led_color_4 = LED_AMBER;
+ else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
+ led_color_4 = LED_WHITE;
else
led_color_4 = LED_OFF;
-
+ led_color_5 = led_color_4;
}
if(new_data_vehicle_gps_position || no_data_vehicle_gps_position < 3) {
- /* handling used sat�s */
+ /* handling used satus */
if(num_of_used_sats >= 7) {
led_color_1 = LED_OFF;
led_color_2 = LED_OFF;
@@ -690,8 +733,11 @@ void BlinkM::setLEDColor(int ledcolor) {
case LED_RED: // red
set_rgb(255,0,0);
break;
+ case LED_ORANGE: // orange
+ set_rgb(255,150,0);
+ break;
case LED_YELLOW: // yellow
- set_rgb(255,70,0);
+ set_rgb(200,200,0);
break;
case LED_PURPLE: // purple
set_rgb(255,0,255);
@@ -702,11 +748,14 @@ void BlinkM::setLEDColor(int ledcolor) {
case LED_BLUE: // blue
set_rgb(0,0,255);
break;
+ case LED_CYAN: // cyan
+ set_rgb(0,128,128);
+ break;
case LED_WHITE: // white
set_rgb(255,255,255);
break;
case LED_AMBER: // amber
- set_rgb(255,20,0);
+ set_rgb(255,65,0);
break;
}
}
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index cf91f7030..e45939b37 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -46,6 +46,10 @@
#define RANGE_FINDER_DEVICE_PATH "/dev/range_finder"
+enum RANGE_FINDER_TYPE {
+ RANGE_FINDER_TYPE_LASER = 0,
+};
+
/**
* range finder report structure. Reads from the device must be in multiples of this
* structure.
@@ -53,8 +57,11 @@
struct range_finder_report {
uint64_t timestamp;
uint64_t error_count;
- float distance; /** in meters */
- uint8_t valid; /** 1 == within sensor range, 0 = outside sensor range */
+ unsigned type; /**< type, following RANGE_FINDER_TYPE enum */
+ float distance; /**< in meters */
+ float minimum_distance; /**< minimum distance the sensor can measure */
+ float maximum_distance; /**< maximum distance the sensor can measure */
+ uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */
};
/*
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index c72f692d7..a902bdf2f 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -282,8 +282,8 @@ GPS::task_main()
_report.p_variance_m = 10.0f;
_report.c_variance_rad = 0.1f;
_report.fix_type = 3;
- _report.eph_m = 10.0f;
- _report.epv_m = 10.0f;
+ _report.eph_m = 3.0f;
+ _report.epv_m = 7.0f;
_report.timestamp_velocity = hrt_absolute_time();
_report.vel_n_m_s = 0.0f;
_report.vel_e_m_s = 0.0f;
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
index 2c3efdc35..1ad383ee0 100644
--- a/src/drivers/meas_airspeed/meas_airspeed.cpp
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -87,6 +87,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/subsystem_info.h>
+#include <uORB/topics/system_power.h>
#include <drivers/airspeed/airspeed.h>
@@ -121,6 +122,14 @@ protected:
virtual int collect();
math::LowPassFilter2p _filter;
+
+ /**
+ * Correct for 5V rail voltage variations
+ */
+ void voltage_correction(float &diff_pres_pa, float &temperature);
+
+ int _t_system_power;
+ struct system_power_s system_power;
};
/*
@@ -129,10 +138,11 @@ protected:
extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]);
MEASAirspeed::MEASAirspeed(int bus, int address, const char *path) : Airspeed(bus, address,
- CONVERSION_INTERVAL, path),
- _filter(MEAS_RATE, MEAS_DRIVER_FILTER_FREQ)
+ CONVERSION_INTERVAL, path),
+ _filter(MEAS_RATE, MEAS_DRIVER_FILTER_FREQ),
+ _t_system_power(-1)
{
-
+ memset(&system_power, 0, sizeof(system_power));
}
int
@@ -194,19 +204,48 @@ MEASAirspeed::collect()
dp_raw = 0x3FFF & dp_raw;
dT_raw = (val[2] << 8) + val[3];
dT_raw = (0xFFE0 & dT_raw) >> 5;
- float temperature = ((200 * dT_raw) / 2047) - 50;
+ float temperature = ((200.0f * dT_raw) / 2047) - 50;
- /* calculate differential pressure. As its centered around 8000
- * and can go positive or negative, enforce absolute value
- */
+ // Calculate differential pressure. As its centered around 8000
+ // and can go positive or negative
const float P_min = -1.0f;
const float P_max = 1.0f;
- float diff_press_pa = fabsf((((float)dp_raw - 0.1f * 16383.0f) * (P_max - P_min) / (0.8f * 16383.0f) + P_min) * 6894.8f) - _diff_pres_offset;
+ const float PSI_to_Pa = 6894.757f;
+ /*
+ this equation is an inversion of the equation in the
+ pressure transfer function figure on page 4 of the datasheet
- if (diff_press_pa < 0.0f) {
- diff_press_pa = 0.0f;
- }
+ We negate the result so that positive differential pressures
+ are generated when the bottom port is used as the static
+ port on the pitot and top port is used as the dynamic port
+ */
+ float diff_press_PSI = -((dp_raw - 0.1f*16383) * (P_max-P_min)/(0.8f*16383) + P_min);
+ float diff_press_pa_raw = diff_press_PSI * PSI_to_Pa;
+ // correct for 5V rail voltage if possible
+ voltage_correction(diff_press_pa_raw, temperature);
+
+ float diff_press_pa = fabsf(diff_press_pa_raw - _diff_pres_offset);
+
+ /*
+ note that we return both the absolute value with offset
+ applied and a raw value without the offset applied. This
+ makes it possible for higher level code to detect if the
+ user has the tubes connected backwards, and also makes it
+ possible to correctly use offsets calculated by a higher
+ level airspeed driver.
+
+ With the above calculation the MS4525 sensor will produce a
+ positive number when the top port is used as a dynamic port
+ and bottom port is used as the static port
+
+ Also note that the _diff_pres_offset is applied before the
+ fabsf() not afterwards. It needs to be done this way to
+ prevent a bias at low speeds, but this also means that when
+ setting a offset you must set it based on the raw value, not
+ the offset value
+ */
+
struct differential_pressure_s report;
/* track maximum differential pressure measured (so we can work out top speed). */
@@ -219,6 +258,13 @@ MEASAirspeed::collect()
report.temperature = temperature;
report.differential_pressure_pa = diff_press_pa;
report.differential_pressure_filtered_pa = _filter.apply(diff_press_pa);
+
+ /* the dynamics of the filter can make it overshoot into the negative range */
+ if (report.differential_pressure_filtered_pa < 0.0f) {
+ report.differential_pressure_filtered_pa = _filter.reset(diff_press_pa);
+ }
+
+ report.differential_pressure_raw_pa = diff_press_pa_raw;
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
@@ -288,6 +334,62 @@ MEASAirspeed::cycle()
}
/**
+ correct for 5V rail voltage if the system_power ORB topic is
+ available
+
+ See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of
+ offset versus voltage for 3 sensors
+ */
+void
+MEASAirspeed::voltage_correction(float &diff_press_pa, float &temperature)
+{
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ if (_t_system_power == -1) {
+ _t_system_power = orb_subscribe(ORB_ID(system_power));
+ }
+ if (_t_system_power == -1) {
+ // not available
+ return;
+ }
+ bool updated = false;
+ orb_check(_t_system_power, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(system_power), _t_system_power, &system_power);
+ }
+ if (system_power.voltage5V_v < 3.0f || system_power.voltage5V_v > 6.0f) {
+ // not valid, skip correction
+ return;
+ }
+
+ const float slope = 65.0f;
+ /*
+ apply a piecewise linear correction, flattening at 0.5V from 5V
+ */
+ float voltage_diff = system_power.voltage5V_v - 5.0f;
+ if (voltage_diff > 0.5f) {
+ voltage_diff = 0.5f;
+ }
+ if (voltage_diff < -0.5f) {
+ voltage_diff = -0.5f;
+ }
+ diff_press_pa -= voltage_diff * slope;
+
+ /*
+ the temperature masurement varies as well
+ */
+ const float temp_slope = 0.887f;
+ voltage_diff = system_power.voltage5V_v - 5.0f;
+ if (voltage_diff > 0.5f) {
+ voltage_diff = 0.5f;
+ }
+ if (voltage_diff < -1.0f) {
+ voltage_diff = -1.0f;
+ }
+ temperature -= voltage_diff * temp_slope;
+#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
+}
+
+/**
* Local functions in support of the shell command.
*/
namespace meas_airspeed
@@ -409,7 +511,7 @@ test()
}
warnx("single read");
- warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
/* start the sensor polling at 2Hz */
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
@@ -437,7 +539,7 @@ test()
}
warnx("periodic read %u", i);
- warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa);
+ warnx("diff pressure: %d pa", (int)report.differential_pressure_pa);
warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
}
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 82f3ba044..e318e206a 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -944,8 +944,23 @@ PX4IO::task_main()
int pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE, &scaling, 1);
if (pret != OK) {
- log("voltage scaling upload failed");
+ log("vscale upload failed");
}
+
+ /* send RC throttle failsafe value to IO */
+ int32_t failsafe_param_val;
+ param_t failsafe_param = param_find("RC_FAILS_THR");
+
+ if (failsafe_param > 0) {
+
+ param_get(failsafe_param, &failsafe_param_val);
+ uint16_t failsafe_thr = failsafe_param_val;
+ pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
+ if (pret != OK) {
+ log("failsafe upload failed");
+ }
+ }
+
}
}
@@ -1479,10 +1494,11 @@ PX4IO::io_publish_raw_rc()
} else {
rc_val.input_source = RC_INPUT_SOURCE_UNKNOWN;
- /* we do not know the RC input, only publish if RC OK flag is set */
- /* if no raw RC, just don't publish */
- if (!(_status & PX4IO_P_STATUS_FLAGS_RC_OK))
+ /* only keep publishing RC input if we ever got a valid input */
+ if (_rc_last_valid == 0) {
+ /* we have never seen valid RC signals, abort */
return OK;
+ }
}
/* lazily advertise on first publication */
diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index dd8abbac5..28ec62356 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -201,9 +201,14 @@ PX4IO_Uploader::upload(const char *filenames[])
continue;
}
- if (bl_rev <= 2)
+ if (bl_rev <= 2) {
ret = verify_rev2(fw_size);
- else if(bl_rev == 3) {
+ } else if(bl_rev == 3) {
+ ret = verify_rev3(fw_size);
+ } else {
+ /* verify rev 4 and higher still uses the same approach and
+ * every version *needs* to be verified.
+ */
ret = verify_rev3(fw_size);
}
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index 07163035b..a0cf98340 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -124,6 +124,8 @@ private:
orb_advert_t _range_finder_topic;
+ unsigned _consecutive_fail_count;
+
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
perf_counter_t _buffer_overflows;
@@ -186,6 +188,7 @@ SF0X::SF0X(const char *port) :
_linebuf_index(0),
_last_read(0),
_range_finder_topic(-1),
+ _consecutive_fail_count(0),
_sample_perf(perf_alloc(PC_ELAPSED, "sf0x_read")),
_comms_errors(perf_alloc(PC_COUNT, "sf0x_comms_errors")),
_buffer_overflows(perf_alloc(PC_COUNT, "sf0x_buffer_overflows"))
@@ -720,12 +723,17 @@ SF0X::cycle()
if (OK != collect_ret) {
/* we know the sensor needs about four seconds to initialize */
- if (hrt_absolute_time() > 5 * 1000 * 1000LL) {
- log("collection error");
+ if (hrt_absolute_time() > 5 * 1000 * 1000LL && _consecutive_fail_count < 5) {
+ log("collection error #%u", _consecutive_fail_count);
}
+ _consecutive_fail_count++;
+
/* restart the measurement state machine */
start();
return;
+ } else {
+ /* apparently success */
+ _consecutive_fail_count = 0;
}
/* next phase is measurement */
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 0b8a275e6..3a60d2cae 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -41,6 +41,7 @@
*/
#include <nuttx/config.h>
+#include <board_config.h>
#include <drivers/device/device.h>
#include <sys/types.h>
@@ -64,6 +65,8 @@
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
+#include <uORB/topics/system_power.h>
+
/*
* Register accessors.
* For now, no reason not to just use ADC1.
@@ -119,6 +122,8 @@ private:
unsigned _channel_count;
adc_msg_s *_samples; /**< sample buffer */
+ orb_advert_t _to_system_power;
+
/** work trampoline */
static void _tick_trampoline(void *arg);
@@ -134,13 +139,16 @@ private:
*/
uint16_t _sample(unsigned channel);
+ // update system_power ORB topic, only on FMUv2
+ void update_system_power(void);
};
ADC::ADC(uint32_t channels) :
CDev("adc", ADC_DEVICE_PATH),
_sample_perf(perf_alloc(PC_ELAPSED, "ADC samples")),
_channel_count(0),
- _samples(nullptr)
+ _samples(nullptr),
+ _to_system_power(0)
{
_debug_enabled = true;
@@ -290,6 +298,43 @@ ADC::_tick()
/* scan the channel set and sample each */
for (unsigned i = 0; i < _channel_count; i++)
_samples[i].am_data = _sample(_samples[i].am_channel);
+ update_system_power();
+}
+
+void
+ADC::update_system_power(void)
+{
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ system_power_s system_power;
+ system_power.timestamp = hrt_absolute_time();
+
+ system_power.voltage5V_v = 0;
+ for (unsigned i = 0; i < _channel_count; i++) {
+ if (_samples[i].am_channel == 4) {
+ // it is 2:1 scaled
+ system_power.voltage5V_v = _samples[i].am_data * (6.6f / 4096);
+ }
+ }
+
+ // these are not ADC related, but it is convenient to
+ // publish these to the same topic
+ system_power.usb_connected = stm32_gpioread(GPIO_OTGFS_VBUS);
+
+ // note that the valid pins are active low
+ system_power.brick_valid = !stm32_gpioread(GPIO_VDD_BRICK_VALID);
+ system_power.servo_valid = !stm32_gpioread(GPIO_VDD_SERVO_VALID);
+
+ // OC pins are active low
+ system_power.periph_5V_OC = !stm32_gpioread(GPIO_VDD_5V_PERIPH_OC);
+ system_power.hipower_5V_OC = !stm32_gpioread(GPIO_VDD_5V_HIPOWER_OC);
+
+ /* lazily publish */
+ if (_to_system_power > 0) {
+ orb_publish(ORB_ID(system_power), _to_system_power, &system_power);
+ } else {
+ _to_system_power = orb_advertise(ORB_ID(system_power), &system_power);
+ }
+#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
}
uint16_t