aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-02-24 20:24:21 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-02-24 20:24:21 +0100
commit35369471db820ba79e9803d4a48ea74ad6843e86 (patch)
treea3c5f01be5140ca6197c740d1a8dc0045820bb49 /apps
parentbde6204b33bdb640e85091c1266ce362820ca7ce (diff)
downloadpx4-firmware-35369471db820ba79e9803d4a48ea74ad6843e86.tar.gz
px4-firmware-35369471db820ba79e9803d4a48ea74ad6843e86.tar.bz2
px4-firmware-35369471db820ba79e9803d4a48ea74ad6843e86.zip
working on better status reporting, removed unneeded fake PWM generation from FMU
Diffstat (limited to 'apps')
-rw-r--r--apps/drivers/px4io/px4io.cpp32
-rw-r--r--apps/sensors/sensors.cpp30
2 files changed, 23 insertions, 39 deletions
diff --git a/apps/drivers/px4io/px4io.cpp b/apps/drivers/px4io/px4io.cpp
index adb894371..a06a2575e 100644
--- a/apps/drivers/px4io/px4io.cpp
+++ b/apps/drivers/px4io/px4io.cpp
@@ -96,6 +96,8 @@ public:
virtual int ioctl(file *filp, int cmd, unsigned long arg);
virtual ssize_t write(file *filp, const char *buffer, size_t len);
+ void print_status();
+
private:
// XXX
unsigned _max_actuators;
@@ -459,7 +461,7 @@ PX4IO::init()
PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK |
PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK, 0);
- /* publish RC config to IO */
+ /* publish RC config to IO */
ret = io_set_rc_config();
if (ret != OK) {
log("failed to update RC input config");
@@ -1141,18 +1143,28 @@ PX4IO::mixer_send(const char *buf, unsigned buflen)
} while (buflen > 0);
- debug("mixer upload OK");
-
/* check for the mixer-OK flag */
- if (io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS) & PX4IO_P_STATUS_FLAGS_MIXER_OK)
+ if (io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS) & PX4IO_P_STATUS_FLAGS_MIXER_OK) {
+ debug("mixer upload OK");
return 0;
-
- debug("mixer rejected by IO");
+ } else {
+ debug("mixer rejected by IO");
+ }
/* load must have failed for some reason */
return -EINVAL;
}
+void
+PX4IO::print_status()
+{
+ printf("\tRC status:\t%s\n", (_status & PX4IO_P_STATUS_FLAGS_RC_OK) ? "OK" : "LOST");
+ if (_status & PX4IO_P_STATUS_FLAGS_RC_OK) {
+ printf("\tRC type:\t%s\n", (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? "S.BUS" : ((_status & PX4IO_P_STATUS_FLAGS_RC_DSM) ? "DSM" : "PPM"));
+ // printf("\tRC chans:\t%d\n", xxx);
+ }
+}
+
int
PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
{
@@ -1294,7 +1306,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg)
}
default:
- /* not a recognised value */
+ /* not a recognized value */
ret = -ENOTTY;
}
@@ -1458,10 +1470,12 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
- if (g_dev != nullptr)
+ if (g_dev != nullptr) {
printf("[px4io] loaded\n");
- else
+ g_dev->print_status();
+ } else {
printf("[px4io] not loaded\n");
+ }
exit(0);
}
diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp
index d8d200ea9..edff8828f 100644
--- a/apps/sensors/sensors.cpp
+++ b/apps/sensors/sensors.cpp
@@ -1074,36 +1074,6 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
void
Sensors::ppm_poll()
{
- /* fake low-level driver, directly pulling from driver variables */
- static orb_advert_t rc_input_pub = -1;
- struct rc_input_values raw;
-
- raw.timestamp = ppm_last_valid_decode;
- /* we are accepting this message */
- _ppm_last_valid = ppm_last_valid_decode;
-
- /*
- * relying on two decoded channels is very noise-prone,
- * in particular if nothing is connected to the pins.
- * requiring a minimum of four channels
- */
- if (ppm_decoded_channels > 4 && hrt_absolute_time() - _ppm_last_valid < PPM_INPUT_TIMEOUT_INTERVAL) {
-
- for (unsigned i = 0; i < ppm_decoded_channels; i++) {
- raw.values[i] = ppm_buffer[i];
- }
-
- raw.channel_count = ppm_decoded_channels;
-
- /* publish to object request broker */
- if (rc_input_pub <= 0) {
- rc_input_pub = orb_advertise(ORB_ID(input_rc), &raw);
-
- } else {
- orb_publish(ORB_ID(input_rc), rc_input_pub, &raw);
- }
- }
-
/* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
bool rc_updated;