aboutsummaryrefslogtreecommitdiff
path: root/src/modules/sensors
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-05-16 12:12:43 +0200
committerAnton Babushkin <anton.babushkin@me.com>2014-05-16 12:12:43 +0200
commit8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af (patch)
treeea6f3edcfa749eb5b0dcc7f307b0fa490d579617 /src/modules/sensors
parentd2553bfd2930eb02664d564559fa361b80c63f61 (diff)
parentf892a7278a4f452c12678fe00c6ff28c2354d548 (diff)
downloadpx4-firmware-8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af.tar.gz
px4-firmware-8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af.tar.bz2
px4-firmware-8c4b35cc23ddf1eaef0dfc90f8fbb066b5b845af.zip
Merge branch 'master' into offboard2
Diffstat (limited to 'src/modules/sensors')
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/sensors/sensor_params.c142
-rw-r--r--src/modules/sensors/sensors.cpp575
3 files changed, 435 insertions, 284 deletions
diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk
index aa538fd6b..5b1bc5e86 100644
--- a/src/modules/sensors/module.mk
+++ b/src/modules/sensors/module.mk
@@ -40,3 +40,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5"
SRCS = sensors.cpp \
sensor_params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 0823f9e70..ae0ff625b 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -488,6 +488,15 @@ PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
+#elif CONFIG_ARCH_BOARD_AEROCORE
+/**
+ * Scaling factor for battery voltage sensor on AeroCore.
+ *
+ * For R70 = 133K, R71 = 10K --> scale = 1.8 * 143 / (4096*10) = 0.0063
+ *
+ * @group Battery Calibration
+ */
+PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0063f);
#else
/**
* Scaling factor for battery voltage sensor on FMU v1.
@@ -536,6 +545,20 @@ PARAM_DEFINE_INT32(RC_MAP_ROLL, 1);
PARAM_DEFINE_INT32(RC_MAP_PITCH, 2);
/**
+ * Failsafe channel mapping.
+ *
+ * The RC mapping index indicates which channel is used for failsafe
+ * If 0, whichever channel is mapped to throttle is used
+ * otherwise the value indicates the specific rc channel to use
+ *
+ * @min 0
+ * @max 18
+ *
+ *
+ */
+PARAM_DEFINE_INT32(RC_MAP_FAILSAFE, 0); //Default to throttle function
+
+/**
* Throttle control channel mapping.
*
* The channel index (starting from 1 for channel 1) indicates
@@ -585,22 +608,30 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
/**
- * Assist switch channel mapping.
+ * Posctl switch channel mapping.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0);
+
+/**
+ * Loiter switch channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
-PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0);
/**
- * Mission switch channel mapping.
+ * Offboard switch channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
-PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
/**
@@ -647,53 +678,106 @@ PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
/**
- * Roll scaling factor
+ * Failsafe channel PWM threshold.
*
+ * @min 800
+ * @max 2200
* @group Radio Calibration
*/
-PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.6f);
+PARAM_DEFINE_INT32(RC_FAILS_THR, 0);
/**
- * Pitch scaling factor
+ * Threshold for selecting assist mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
*
- * @group Radio Calibration
*/
-PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.6f);
+PARAM_DEFINE_FLOAT(RC_ASSIST_TH, 0.25f);
/**
- * Yaw scaling factor
+ * Threshold for selecting auto mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
*
- * @group Radio Calibration
*/
-PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 2.0f);
+PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f);
+/**
+ * Threshold for selecting posctl mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_POSCTL_TH, 0.5f);
/**
- * Failsafe channel mapping.
+ * Threshold for selecting return to launch mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
*
- * @min 0
- * @max 18
- * @group Radio Calibration
*/
-PARAM_DEFINE_INT32(RC_FS_CH, 0);
+PARAM_DEFINE_FLOAT(RC_RETURN_TH, 0.5f);
/**
- * Failsafe channel mode.
+ * Threshold for selecting loiter mode
*
- * 0 = too low means signal loss,
- * 1 = too high means signal loss
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
*
- * @min 0
- * @max 1
- * @group Radio Calibration
*/
-PARAM_DEFINE_INT32(RC_FS_MODE, 0);
+PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f);
/**
- * Failsafe channel PWM threshold.
+ * Threshold for selecting offboard mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
*
- * @min 0
- * @max 1
- * @group Radio Calibration
*/
-PARAM_DEFINE_FLOAT(RC_FS_THR, 800);
+PARAM_DEFINE_FLOAT(RC_OFFB_TH, 0.5f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 45e7035de..f34263a96 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -36,6 +36,8 @@
* Sensor readout process.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
#include <nuttx/config.h>
@@ -124,6 +126,12 @@
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+#define ADC_BATTERY_VOLTAGE_CHANNEL 10
+#define ADC_BATTERY_CURRENT_CHANNEL -1
+#define ADC_AIRSPEED_VOLTAGE_CHANNEL -1
+#endif
+
#define BATT_V_LOWPASS 0.001f
#define BATT_V_IGNORE_THRESHOLD 3.5f
@@ -133,7 +141,7 @@
*/
#define PCB_TEMP_ESTIMATE_DEG 5.0f
-#define limit_minus_one_to_one(arg) (arg < -1.0f) ? -1.0f : ((arg > 1.0f) ? 1.0f : arg)
+#define STICK_ON_OFF_LIMIT 0.75f
/**
* Sensor app start / stop handling function
@@ -165,7 +173,16 @@ public:
private:
static const unsigned _rc_max_chan_count = RC_INPUT_MAX_CHANNELS; /**< maximum number of r/c channels we handle */
- hrt_abstime _rc_last_valid; /**< last time we got a valid RC signal */
+ /**
+ * Get and limit value for specified RC function. Returns NAN if not mapped.
+ */
+ float get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max_value);
+
+ /**
+ * Get switch position for specified function.
+ */
+ switch_pos_t get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv);
+ switch_pos_t get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv);
/**
* Gather and publish RC input data.
@@ -209,8 +226,8 @@ private:
struct differential_pressure_s _diff_pres;
struct airspeed_s _airspeed;
- math::Matrix<3,3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
- math::Matrix<3,3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
+ math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
+ math::Matrix<3, 3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
bool _mag_is_external; /**< true if the active mag is on an external board */
uint64_t _battery_discharged; /**< battery discharged current in mA*ms */
@@ -240,11 +257,12 @@ private:
int rc_map_pitch;
int rc_map_yaw;
int rc_map_throttle;
+ int rc_map_failsafe;
int rc_map_mode_sw;
int rc_map_return_sw;
- int rc_map_assisted_sw;
- int rc_map_mission_sw;
+ int rc_map_posctl_sw;
+ int rc_map_loiter_sw;
int rc_map_offboard_sw;
int rc_map_flaps;
@@ -255,14 +273,19 @@ private:
int rc_map_aux4;
int rc_map_aux5;
- float rc_scale_roll;
- float rc_scale_pitch;
- float rc_scale_yaw;
- float rc_scale_flaps;
-
- int rc_fs_ch;
- int rc_fs_mode;
- float rc_fs_thr;
+ int32_t rc_fails_thr;
+ float rc_assist_th;
+ float rc_auto_th;
+ float rc_posctl_th;
+ float rc_return_th;
+ float rc_loiter_th;
+ float rc_offboard_th;
+ bool rc_assist_inv;
+ bool rc_auto_inv;
+ bool rc_posctl_inv;
+ bool rc_return_inv;
+ bool rc_loiter_inv;
+ bool rc_offboard_inv;
float battery_voltage_scaling;
float battery_current_scaling;
@@ -289,11 +312,12 @@ private:
param_t rc_map_pitch;
param_t rc_map_yaw;
param_t rc_map_throttle;
+ param_t rc_map_failsafe;
param_t rc_map_mode_sw;
param_t rc_map_return_sw;
- param_t rc_map_assisted_sw;
- param_t rc_map_mission_sw;
+ param_t rc_map_posctl_sw;
+ param_t rc_map_loiter_sw;
param_t rc_map_offboard_sw;
param_t rc_map_flaps;
@@ -304,14 +328,13 @@ private:
param_t rc_map_aux4;
param_t rc_map_aux5;
- param_t rc_scale_roll;
- param_t rc_scale_pitch;
- param_t rc_scale_yaw;
- param_t rc_scale_flaps;
-
- param_t rc_fs_ch;
- param_t rc_fs_mode;
- param_t rc_fs_thr;
+ param_t rc_fails_thr;
+ param_t rc_assist_th;
+ param_t rc_auto_th;
+ param_t rc_posctl_th;
+ param_t rc_return_th;
+ param_t rc_loiter_th;
+ param_t rc_offboard_th;
param_t battery_voltage_scaling;
param_t battery_current_scaling;
@@ -418,7 +441,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace sensors
@@ -434,8 +457,6 @@ Sensors *g_sensors = nullptr;
}
Sensors::Sensors() :
- _rc_last_valid(0),
-
_fd_adc(-1),
_last_adc(0),
@@ -470,6 +491,7 @@ Sensors::Sensors() :
_battery_discharged(0),
_battery_current_timestamp(0)
{
+ memset(&_rc, 0, sizeof(_rc));
/* basic r/c parameters */
for (unsigned i = 0; i < _rc_max_chan_count; i++) {
@@ -502,6 +524,7 @@ Sensors::Sensors() :
_parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
_parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW");
_parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE");
+ _parameter_handles.rc_map_failsafe = param_find("RC_MAP_FAILSAFE");
/* mandatory mode switches, mapped to channel 5 and 6 per default */
_parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW");
@@ -510,8 +533,8 @@ Sensors::Sensors() :
_parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
/* optional mode switches, not mapped per default */
- _parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW");
- _parameter_handles.rc_map_mission_sw = param_find("RC_MAP_MISSIO_SW");
+ _parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
+ _parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
_parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
@@ -520,15 +543,14 @@ Sensors::Sensors() :
_parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4");
_parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
- _parameter_handles.rc_scale_roll = param_find("RC_SCALE_ROLL");
- _parameter_handles.rc_scale_pitch = param_find("RC_SCALE_PITCH");
- _parameter_handles.rc_scale_yaw = param_find("RC_SCALE_YAW");
- _parameter_handles.rc_scale_flaps = param_find("RC_SCALE_FLAPS");
-
- /* RC failsafe */
- _parameter_handles.rc_fs_ch = param_find("RC_FS_CH");
- _parameter_handles.rc_fs_mode = param_find("RC_FS_MODE");
- _parameter_handles.rc_fs_thr = param_find("RC_FS_THR");
+ /* RC thresholds */
+ _parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
+ _parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH");
+ _parameter_handles.rc_auto_th = param_find("RC_AUTO_TH");
+ _parameter_handles.rc_posctl_th = param_find("RC_POSCTL_TH");
+ _parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
+ _parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
+ _parameter_handles.rc_offboard_th = param_find("RC_OFFB_TH");
/* gyro offsets */
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
@@ -629,50 +651,55 @@ Sensors::parameters_update()
}
/* handle wrong values */
- if (!rc_valid)
+ if (!rc_valid) {
warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
+ }
const char *paramerr = "FAIL PARM LOAD";
/* channel mapping */
if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_pitch, &(_parameters.rc_map_pitch)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_yaw, &(_parameters.rc_map_yaw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_throttle, &(_parameters.rc_map_throttle)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
+ }
+
+ if (param_get(_parameter_handles.rc_map_failsafe, &(_parameters.rc_map_failsafe)) != OK) {
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_return_sw, &(_parameters.rc_map_return_sw)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
- if (param_get(_parameter_handles.rc_map_assisted_sw, &(_parameters.rc_map_assisted_sw)) != OK) {
- warnx(paramerr);
+ if (param_get(_parameter_handles.rc_map_posctl_sw, &(_parameters.rc_map_posctl_sw)) != OK) {
+ warnx("%s", paramerr);
}
- if (param_get(_parameter_handles.rc_map_mission_sw, &(_parameters.rc_map_mission_sw)) != OK) {
- warnx(paramerr);
+ if (param_get(_parameter_handles.rc_map_loiter_sw, &(_parameters.rc_map_loiter_sw)) != OK) {
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_offboard_sw, &(_parameters.rc_map_offboard_sw)) != OK) {
- warnx("Failed getting offboard sw chan index");
+ warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1));
@@ -680,13 +707,25 @@ Sensors::parameters_update()
param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
- param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll));
- param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch));
- param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw));
- param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps));
- param_get(_parameter_handles.rc_fs_ch, &(_parameters.rc_fs_ch));
- param_get(_parameter_handles.rc_fs_mode, &(_parameters.rc_fs_mode));
- param_get(_parameter_handles.rc_fs_thr, &(_parameters.rc_fs_thr));
+ param_get(_parameter_handles.rc_fails_thr, &(_parameters.rc_fails_thr));
+ param_get(_parameter_handles.rc_assist_th, &(_parameters.rc_assist_th));
+ _parameters.rc_assist_inv = (_parameters.rc_assist_th < 0);
+ _parameters.rc_assist_th = fabs(_parameters.rc_assist_th);
+ param_get(_parameter_handles.rc_auto_th, &(_parameters.rc_auto_th));
+ _parameters.rc_auto_inv = (_parameters.rc_auto_th < 0);
+ _parameters.rc_auto_th = fabs(_parameters.rc_auto_th);
+ param_get(_parameter_handles.rc_posctl_th, &(_parameters.rc_posctl_th));
+ _parameters.rc_posctl_inv = (_parameters.rc_posctl_th < 0);
+ _parameters.rc_posctl_th = fabs(_parameters.rc_posctl_th);
+ param_get(_parameter_handles.rc_return_th, &(_parameters.rc_return_th));
+ _parameters.rc_return_inv = (_parameters.rc_return_th < 0);
+ _parameters.rc_return_th = fabs(_parameters.rc_return_th);
+ param_get(_parameter_handles.rc_loiter_th, &(_parameters.rc_loiter_th));
+ _parameters.rc_loiter_inv = (_parameters.rc_loiter_th < 0);
+ _parameters.rc_loiter_th = fabs(_parameters.rc_loiter_th);
+ param_get(_parameter_handles.rc_offboard_th, &(_parameters.rc_offboard_th));
+ _parameters.rc_offboard_inv = (_parameters.rc_offboard_th < 0);
+ _parameters.rc_offboard_th = fabs(_parameters.rc_offboard_th);
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -696,9 +735,9 @@ Sensors::parameters_update()
_rc.function[MODE] = _parameters.rc_map_mode_sw - 1;
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
- _rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1;
- _rc.function[MISSION] = _parameters.rc_map_mission_sw - 1;
- _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_sw - 1;
+ _rc.function[POSCTL] = _parameters.rc_map_posctl_sw - 1;
+ _rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
+ _rc.function[OFFBOARD] = _parameters.rc_map_offboard_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
@@ -739,12 +778,12 @@ Sensors::parameters_update()
/* scaling of ADC ticks to battery voltage */
if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
/* scaling of ADC ticks to battery current */
if (param_get(_parameter_handles.battery_current_scaling, &(_parameters.battery_current_scaling)) != OK) {
- warnx(paramerr);
+ warnx("%s", paramerr);
}
param_get(_parameter_handles.board_rotation, &(_parameters.board_rotation));
@@ -779,7 +818,7 @@ Sensors::accel_init()
/* set the driver to poll at 1000Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 1000);
-#elif CONFIG_ARCH_BOARD_PX4FMU_V2
+#elif CONFIG_ARCH_BOARD_PX4FMU_V2 || CONFIG_ARCH_BOARD_AEROCORE
/* set the accel internal sampling rate up to at leat 800Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 800);
@@ -788,7 +827,7 @@ Sensors::accel_init()
ioctl(fd, SENSORIOCSPOLLRATE, 800);
#else
-#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
+#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1, CONFIG_ARCH_BOARD_PX4FMU_V2 or CONFIG_ARCH_BOARD_AEROCORE
#endif
@@ -814,12 +853,14 @@ Sensors::gyro_init()
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* set the gyro internal sampling rate up to at least 1000Hz */
- if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK)
+ if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK) {
ioctl(fd, GYROIOCSSAMPLERATE, 800);
+ }
/* set the driver to poll at 1000Hz */
- if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK) {
ioctl(fd, SENSORIOCSPOLLRATE, 800);
+ }
#else
@@ -874,12 +915,15 @@ Sensors::mag_init()
ret = ioctl(fd, MAGIOCGEXTERNAL, 0);
- if (ret < 0)
+ if (ret < 0) {
errx(1, "FATAL: unknown if magnetometer is external or onboard");
- else if (ret == 1)
+
+ } else if (ret == 1) {
_mag_is_external = true;
- else
+
+ } else {
_mag_is_external = false;
+ }
close(fd);
}
@@ -979,10 +1023,12 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
math::Vector<3> vect(mag_report.x, mag_report.y, mag_report.z);
- if (_mag_is_external)
+ if (_mag_is_external) {
vect = _external_mag_rotation * vect;
- else
+
+ } else {
vect = _board_rotation * vect;
+ }
raw.magnetometer_ga[0] = vect(0);
raw.magnetometer_ga[1] = vect(1);
@@ -1027,10 +1073,13 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
raw.differential_pressure_timestamp = _diff_pres.timestamp;
raw.differential_pressure_filtered_pa = _diff_pres.differential_pressure_filtered_pa;
+ float air_temperature_celsius = (_diff_pres.temperature > -300.0f) ? _diff_pres.temperature : (raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
+
_airspeed.timestamp = _diff_pres.timestamp;
_airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_filtered_pa);
_airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_filtered_pa + raw.baro_pres_mbar * 1e2f,
- raw.baro_pres_mbar * 1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
+ raw.baro_pres_mbar * 1e2f, air_temperature_celsius);
+ _airspeed.air_temperature_celsius = air_temperature_celsius;
/* announce the airspeed if needed, just publish else */
if (_airspeed_pub > 0) {
@@ -1097,8 +1146,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.gyro_scale[2],
};
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale)) {
warn("WARNING: failed to set scale / offsets for gyro");
+ }
close(fd);
@@ -1112,8 +1162,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.accel_scale[2],
};
- if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale))
+ if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale)) {
warn("WARNING: failed to set scale / offsets for accel");
+ }
close(fd);
@@ -1127,8 +1178,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.mag_scale[2],
};
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
+ if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale)) {
warn("WARNING: failed to set scale / offsets for mag");
+ }
close(fd);
@@ -1142,8 +1194,10 @@ Sensors::parameter_update_poll(bool forced)
1.0f,
};
- if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale))
+ if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
warn("WARNING: failed to set scale / offsets for airspeed sensor");
+ }
+
close(fd);
}
@@ -1161,22 +1215,27 @@ void
Sensors::adc_poll(struct sensor_combined_s &raw)
{
/* only read if publishing */
- if (!_publishing)
+ if (!_publishing) {
return;
+ }
hrt_abstime t = hrt_absolute_time();
+
/* rate limit to 100 Hz */
if (t - _last_adc >= 10000) {
- /* make space for a maximum of eight channels */
- struct adc_msg_s buf_adc[8];
+ /* make space for a maximum of twelve channels (to ensure reading all channels at once) */
+ struct adc_msg_s buf_adc[12];
/* read all channels available */
int ret = read(_fd_adc, &buf_adc, sizeof(buf_adc));
if (ret >= (int)sizeof(buf_adc[0])) {
- for (unsigned i = 0; i < sizeof(buf_adc) / sizeof(buf_adc[0]); i++) {
+
+ /* Read add channels we got */
+ for (unsigned i = 0; i < ret / sizeof(buf_adc[0]); i++) {
/* Save raw voltage values */
- if (i < (sizeof(raw.adc_voltage_v)) / sizeof(raw.adc_voltage_v[0])) {
+ if (i < (sizeof(raw.adc_voltage_v) / sizeof(raw.adc_voltage_v[0]))) {
raw.adc_voltage_v[i] = buf_adc[i].am_data / (4096.0f / 3.3f);
+ raw.adc_mapping[i] = buf_adc[i].am_channel;
}
/* look for specific channels and process the raw voltage to measurement data */
@@ -1186,6 +1245,7 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
if (voltage > BATT_V_IGNORE_THRESHOLD) {
_battery_status.voltage_v = voltage;
+
/* one-time initialization of low-pass value to avoid long init delays */
if (_battery_status.voltage_filtered_v < BATT_V_IGNORE_THRESHOLD) {
_battery_status.voltage_filtered_v = voltage;
@@ -1204,19 +1264,24 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
/* handle current only if voltage is valid */
if (_battery_status.voltage_v > 0.0f) {
float current = (buf_adc[i].am_data * _parameters.battery_current_scaling);
+
/* check measured current value */
if (current >= 0.0f) {
_battery_status.timestamp = t;
_battery_status.current_a = current;
+
if (_battery_current_timestamp != 0) {
/* initialize discharged value */
- if (_battery_status.discharged_mah < 0.0f)
+ if (_battery_status.discharged_mah < 0.0f) {
_battery_status.discharged_mah = 0.0f;
+ }
+
_battery_discharged += current * (t - _battery_current_timestamp);
_battery_status.discharged_mah = ((float) _battery_discharged) / 3600000.0f;
}
}
}
+
_battery_current_timestamp = t;
} else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) {
@@ -1235,6 +1300,8 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
_diff_pres.timestamp = t;
_diff_pres.differential_pressure_pa = diff_pres_pa;
+ _diff_pres.differential_pressure_filtered_pa = diff_pres_pa;
+ _diff_pres.temperature = -1000.0f;
_diff_pres.voltage = voltage;
/* announce the airspeed if needed, just publish else */
@@ -1247,8 +1314,10 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
}
}
+
_last_adc = t;
- if (_battery_status.voltage_v > 0.0f) {
+
+ if (_battery_status.voltage_filtered_v > BATT_V_IGNORE_THRESHOLD) {
/* announce the battery status if needed, just publish else */
if (_battery_pub > 0) {
orb_publish(ORB_ID(battery_status), _battery_pub, &_battery_status);
@@ -1261,6 +1330,66 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
}
+float
+Sensors::get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max_value)
+{
+ if (_rc.function[func] >= 0) {
+ float value = _rc.chan[_rc.function[func]].scaled;
+
+ if (value < min_value) {
+ return min_value;
+
+ } else if (value > max_value) {
+ return max_value;
+
+ } else {
+ return value;
+ }
+
+ } else {
+ return 0.0f;
+ }
+}
+
+switch_pos_t
+Sensors::get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv)
+{
+ if (_rc.function[func] >= 0) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+
+ if (on_inv ? value < on_th : value > on_th) {
+ return SWITCH_POS_ON;
+
+ } else if (mid_inv ? value < mid_th : value > mid_th) {
+ return SWITCH_POS_MIDDLE;
+
+ } else {
+ return SWITCH_POS_OFF;
+ }
+
+ } else {
+ return SWITCH_POS_NONE;
+ }
+}
+
+switch_pos_t
+Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv)
+{
+ if (_rc.function[func] >= 0) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+
+ if (on_inv ? value < on_th : value > on_th) {
+ return SWITCH_POS_ON;
+
+ } else {
+ return SWITCH_POS_OFF;
+ }
+
+ } else {
+ return SWITCH_POS_NONE;
+ }
+}
+
void
Sensors::rc_poll()
{
@@ -1269,70 +1398,58 @@ Sensors::rc_poll()
if (rc_updated) {
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
- struct rc_input_values rc_input;
+ struct rc_input_values rc_input;
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
- if (rc_input.rc_lost)
- return;
-
- struct manual_control_setpoint_s manual_control;
- struct actuator_controls_s actuator_group_3;
-
- /* initialize to default values */
- manual_control.roll = NAN;
- manual_control.pitch = NAN;
- manual_control.yaw = NAN;
- manual_control.throttle = NAN;
-
- manual_control.mode_switch = NAN;
- manual_control.return_switch = NAN;
- manual_control.assisted_switch = NAN;
- manual_control.mission_switch = NAN;
- manual_control.offboard_switch = NAN;
-
- manual_control.flaps = NAN;
- manual_control.aux1 = NAN;
- manual_control.aux2 = NAN;
- manual_control.aux3 = NAN;
- manual_control.aux4 = NAN;
- manual_control.aux5 = NAN;
-
- /* require at least four channels to consider the signal valid */
- if (rc_input.channel_count < 4)
- return;
-
- /* failsafe check */
- if (_parameters.rc_fs_ch != 0) {
- if (_parameters.rc_fs_mode == 0) {
- if (rc_input.values[_parameters.rc_fs_ch - 1] < _parameters.rc_fs_thr)
- return;
-
- } else if (_parameters.rc_fs_mode == 1) {
- if (rc_input.values[_parameters.rc_fs_ch - 1] > _parameters.rc_fs_thr)
- return;
+ /* detect RC signal loss */
+ bool signal_lost;
+
+ /* check flags and require at least four channels to consider the signal valid */
+ if (rc_input.rc_lost || rc_input.rc_failsafe || rc_input.channel_count < 4) {
+ /* signal is lost or no enough channels */
+ signal_lost = true;
+
+ } else {
+ /* signal looks good */
+ signal_lost = false;
+
+ /* check failsafe */
+ int8_t fs_ch = _rc.function[_parameters.rc_map_failsafe]; // get channel mapped to throttle
+
+ if (_parameters.rc_map_failsafe > 0) { // if not 0, use channel number instead of rc.function mapping
+ fs_ch = _parameters.rc_map_failsafe - 1;
+ }
+
+ if (_parameters.rc_fails_thr > 0 && fs_ch >= 0) {
+ /* failsafe configured */
+ if ((_parameters.rc_fails_thr < _parameters.min[fs_ch] && rc_input.values[fs_ch] < _parameters.rc_fails_thr) ||
+ (_parameters.rc_fails_thr > _parameters.max[fs_ch] && rc_input.values[fs_ch] > _parameters.rc_fails_thr)) {
+ /* failsafe triggered, signal is lost by receiver */
+ signal_lost = true;
+ }
}
}
unsigned channel_limit = rc_input.channel_count;
- if (channel_limit > _rc_max_chan_count)
+ if (channel_limit > _rc_max_chan_count) {
channel_limit = _rc_max_chan_count;
+ }
- /* we are accepting this message */
- _rc_last_valid = rc_input.timestamp_last_signal;
-
- /* Read out values from raw message */
+ /* read out and scale values from raw message even if signal is invalid */
for (unsigned int i = 0; i < channel_limit; i++) {
/*
* 1) Constrain to min/max values, as later processing depends on bounds.
*/
- if (rc_input.values[i] < _parameters.min[i])
+ if (rc_input.values[i] < _parameters.min[i]) {
rc_input.values[i] = _parameters.min[i];
+ }
- if (rc_input.values[i] > _parameters.max[i])
+ if (rc_input.values[i] > _parameters.max[i]) {
rc_input.values[i] = _parameters.max[i];
+ }
/*
* 2) Scale around the mid point differently for lower and upper range.
@@ -1364,136 +1481,82 @@ Sensors::rc_poll()
_rc.chan[i].scaled *= _parameters.rev[i];
/* handle any parameter-induced blowups */
- if (!isfinite(_rc.chan[i].scaled))
+ if (!isfinite(_rc.chan[i].scaled)) {
_rc.chan[i].scaled = 0.0f;
+ }
}
_rc.chan_count = rc_input.channel_count;
+ _rc.rssi = rc_input.rssi;
+ _rc.signal_lost = signal_lost;
_rc.timestamp = rc_input.timestamp_last_signal;
- manual_control.timestamp = rc_input.timestamp_last_signal;
-
- /* roll input - rolling right is stick-wise and rotation-wise positive */
- manual_control.roll = limit_minus_one_to_one(_rc.chan[_rc.function[ROLL]].scaled);
- /*
- * pitch input - stick down is negative, but stick down is pitching up (pos) in NED,
- * so reverse sign.
- */
- manual_control.pitch = limit_minus_one_to_one(-1.0f * _rc.chan[_rc.function[PITCH]].scaled);
- /* yaw input - stick right is positive and positive rotation */
- manual_control.yaw = limit_minus_one_to_one(_rc.chan[_rc.function[YAW]].scaled);
- /* throttle input */
- manual_control.throttle = _rc.chan[_rc.function[THROTTLE]].scaled;
-
- if (manual_control.throttle < 0.0f) manual_control.throttle = 0.0f;
-
- if (manual_control.throttle > 1.0f) manual_control.throttle = 1.0f;
-
- /* scale output */
- if (isfinite(_parameters.rc_scale_roll) && _parameters.rc_scale_roll > 0.0f) {
- manual_control.roll *= _parameters.rc_scale_roll;
- }
-
- if (isfinite(_parameters.rc_scale_pitch) && _parameters.rc_scale_pitch > 0.0f) {
- manual_control.pitch *= _parameters.rc_scale_pitch;
- }
-
- if (isfinite(_parameters.rc_scale_yaw) && _parameters.rc_scale_yaw > 0.0f) {
- manual_control.yaw *= _parameters.rc_scale_yaw;
- }
-
- /* flaps */
- if (_rc.function[FLAPS] >= 0) {
-
- manual_control.flaps = limit_minus_one_to_one(_rc.chan[_rc.function[FLAPS]].scaled);
-
- if (isfinite(_parameters.rc_scale_flaps) && _parameters.rc_scale_flaps > 0.0f) {
- manual_control.flaps *= _parameters.rc_scale_flaps;
- }
- }
-
- /* mode switch input */
- if (_rc.function[MODE] >= 0) {
- manual_control.mode_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MODE]].scaled);
- }
-
- /* assisted switch input */
- if (_rc.function[ASSISTED] >= 0) {
- manual_control.assisted_switch = limit_minus_one_to_one(_rc.chan[_rc.function[ASSISTED]].scaled);
- }
-
- /* mission switch input */
- if (_rc.function[MISSION] >= 0) {
- manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
- }
-
- /* return switch input */
- if (_rc.function[RETURN] >= 0) {
- manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled);
- }
-
- /* offboard switch input */
- if (_rc.function[OFFBOARD_MODE] >= 0) {
- manual_control.offboard_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
- }
-
- /* aux functions, only assign if valid mapping is present */
- if (_rc.function[AUX_1] >= 0) {
- manual_control.aux1 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_1]].scaled);
- }
-
- if (_rc.function[AUX_2] >= 0) {
- manual_control.aux2 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_2]].scaled);
- }
-
- if (_rc.function[AUX_3] >= 0) {
- manual_control.aux3 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_3]].scaled);
- }
-
- if (_rc.function[AUX_4] >= 0) {
- manual_control.aux4 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_4]].scaled);
- }
-
- if (_rc.function[AUX_5] >= 0) {
- manual_control.aux5 = limit_minus_one_to_one(_rc.chan[_rc.function[AUX_5]].scaled);
- }
-
- /* copy from mapped manual control to control group 3 */
- actuator_group_3.control[0] = manual_control.roll;
- actuator_group_3.control[1] = manual_control.pitch;
- actuator_group_3.control[2] = manual_control.yaw;
- actuator_group_3.control[3] = manual_control.throttle;
- actuator_group_3.control[4] = manual_control.flaps;
- actuator_group_3.control[5] = manual_control.aux1;
- actuator_group_3.control[6] = manual_control.aux2;
- actuator_group_3.control[7] = manual_control.aux3;
-
- /* check if ready for publishing */
+ /* publish rc_channels topic even if signal is invalid, for debug */
if (_rc_pub > 0) {
orb_publish(ORB_ID(rc_channels), _rc_pub, &_rc);
} else {
- /* advertise the rc topic */
_rc_pub = orb_advertise(ORB_ID(rc_channels), &_rc);
}
- /* check if ready for publishing */
- if (_manual_control_pub > 0) {
- orb_publish(ORB_ID(manual_control_setpoint), _manual_control_pub, &manual_control);
+ if (!signal_lost) {
+ struct manual_control_setpoint_s manual;
+ memset(&manual, 0 , sizeof(manual));
+
+ /* fill values in manual_control_setpoint topic only if signal is valid */
+ manual.timestamp = rc_input.timestamp_last_signal;
+
+ /* limit controls */
+ manual.y = get_rc_value(ROLL, -1.0, 1.0);
+ manual.x = get_rc_value(PITCH, -1.0, 1.0);
+ manual.r = get_rc_value(YAW, -1.0, 1.0);
+ manual.z = get_rc_value(THROTTLE, 0.0, 1.0);
+ manual.flaps = get_rc_value(FLAPS, -1.0, 1.0);
+ manual.aux1 = get_rc_value(AUX_1, -1.0, 1.0);
+ manual.aux2 = get_rc_value(AUX_2, -1.0, 1.0);
+ manual.aux3 = get_rc_value(AUX_3, -1.0, 1.0);
+ manual.aux4 = get_rc_value(AUX_4, -1.0, 1.0);
+ manual.aux5 = get_rc_value(AUX_5, -1.0, 1.0);
+
+ /* mode switches */
+ manual.mode_switch = get_rc_sw3pos_position(MODE, _parameters.rc_auto_th, _parameters.rc_auto_inv, _parameters.rc_assist_th, _parameters.rc_assist_inv);
+ manual.posctl_switch = get_rc_sw2pos_position(POSCTL, _parameters.rc_posctl_th, _parameters.rc_posctl_inv);
+ manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
+ manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
+ manual.offboard_switch = get_rc_sw2pos_position(OFFBOARD, _parameters.rc_offboard_th, _parameters.rc_offboard_inv);
+
+ /* publish manual_control_setpoint topic */
+ if (_manual_control_pub > 0) {
+ orb_publish(ORB_ID(manual_control_setpoint), _manual_control_pub, &manual);
- } else {
- _manual_control_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual_control);
- }
+ } else {
+ _manual_control_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
+ }
- /* check if ready for publishing */
- if (_actuator_group_3_pub > 0) {
- orb_publish(ORB_ID(actuator_controls_3), _actuator_group_3_pub, &actuator_group_3);
+ /* copy from mapped manual control to control group 3 */
+ struct actuator_controls_s actuator_group_3;
+ memset(&actuator_group_3, 0 , sizeof(actuator_group_3));
- } else {
- _actuator_group_3_pub = orb_advertise(ORB_ID(actuator_controls_3), &actuator_group_3);
+ actuator_group_3.timestamp = rc_input.timestamp_last_signal;
+
+ actuator_group_3.control[0] = manual.y;
+ actuator_group_3.control[1] = manual.x;
+ actuator_group_3.control[2] = manual.r;
+ actuator_group_3.control[3] = manual.z;
+ actuator_group_3.control[4] = manual.flaps;
+ actuator_group_3.control[5] = manual.aux1;
+ actuator_group_3.control[6] = manual.aux2;
+ actuator_group_3.control[7] = manual.aux3;
+
+ /* publish actuator_controls_3 topic */
+ if (_actuator_group_3_pub > 0) {
+ orb_publish(ORB_ID(actuator_controls_3), _actuator_group_3_pub, &actuator_group_3);
+
+ } else {
+ _actuator_group_3_pub = orb_advertise(ORB_ID(actuator_controls_3), &actuator_group_3);
+ }
}
}
-
}
void
@@ -1570,12 +1633,10 @@ Sensors::task_main()
while (!_task_should_exit) {
- /* wait for up to 100ms for data */
- int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
+ /* wait for up to 50ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 50);
- /* timed out - periodic check for _task_should_exit, etc. */
- if (pret == 0)
- continue;
+ /* if pret == 0 it timed out - periodic check for _task_should_exit, etc. */
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -1605,8 +1666,9 @@ Sensors::task_main()
diff_pres_poll(raw);
/* Inform other processes that new data is available to copy */
- if (_publishing)
+ if (_publishing) {
orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw);
+ }
/* Look for new r/c input data */
rc_poll();
@@ -1614,7 +1676,7 @@ Sensors::task_main()
perf_end(_loop_perf);
}
- printf("[sensors] exiting.\n");
+ warnx("[sensors] exiting.");
_sensors_task = -1;
_exit(0);
@@ -1629,7 +1691,7 @@ Sensors::start()
_sensors_task = task_spawn_cmd("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&Sensors::task_main_trampoline,
nullptr);
@@ -1643,18 +1705,21 @@ Sensors::start()
int sensors_main(int argc, char *argv[])
{
- if (argc < 1)
+ if (argc < 1) {
errx(1, "usage: sensors {start|stop|status}");
+ }
if (!strcmp(argv[1], "start")) {
- if (sensors::g_sensors != nullptr)
+ if (sensors::g_sensors != nullptr) {
errx(0, "already running");
+ }
sensors::g_sensors = new Sensors;
- if (sensors::g_sensors == nullptr)
+ if (sensors::g_sensors == nullptr) {
errx(1, "alloc failed");
+ }
if (OK != sensors::g_sensors->start()) {
delete sensors::g_sensors;
@@ -1666,8 +1731,9 @@ int sensors_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "stop")) {
- if (sensors::g_sensors == nullptr)
+ if (sensors::g_sensors == nullptr) {
errx(1, "not running");
+ }
delete sensors::g_sensors;
sensors::g_sensors = nullptr;
@@ -1686,4 +1752,3 @@ int sensors_main(int argc, char *argv[])
warnx("unrecognized command");
return 1;
}
-