aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2012-11-10 15:22:42 +0100
committerThomas Gubler <thomasgubler@gmail.com>2012-11-10 15:22:42 +0100
commit536ab4bce3f68f443ef9d1ab16c7e49011af656a (patch)
tree44cc43f9cac229fe9044d51a1ddd6ef6e996f411
parent8768b7ddbf0a2e420555072d21ce3ec95e373c01 (diff)
parent90466afe05359cd5fc1d5b44b13d73912fb6571b (diff)
downloadpx4-firmware-536ab4bce3f68f443ef9d1ab16c7e49011af656a.tar.gz
px4-firmware-536ab4bce3f68f443ef9d1ab16c7e49011af656a.tar.bz2
px4-firmware-536ab4bce3f68f443ef9d1ab16c7e49011af656a.zip
Merge branch 'master' of https://github.com/PX4/Firmware into fw_control
-rw-r--r--apps/mavlink/mavlink_receiver.c4
-rw-r--r--apps/mavlink/orb_listener.c4
-rw-r--r--apps/multirotor_pos_control/multirotor_pos_control.c6
-rw-r--r--apps/px4/tests/test_adc.c175
-rw-r--r--apps/px4/tests/test_sensors.c141
-rw-r--r--apps/sensors/sensors.cpp4
-rw-r--r--apps/uORB/topics/subsystem_info.h12
7 files changed, 206 insertions, 140 deletions
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index 39e574c04..e1a4e8e8a 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +35,8 @@
/**
* @file mavlink_receiver.c
* MAVLink protocol message receive and dispatch
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
/* XXX trim includes */
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 50cf9cf3d..928de5a38 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +35,8 @@
/**
* @file orb_listener.c
* Monitors ORB topics and sends update messages as appropriate.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
// XXX trim includes
diff --git a/apps/multirotor_pos_control/multirotor_pos_control.c b/apps/multirotor_pos_control/multirotor_pos_control.c
index 9821fc7e5..7b8d83aa8 100644
--- a/apps/multirotor_pos_control/multirotor_pos_control.c
+++ b/apps/multirotor_pos_control/multirotor_pos_control.c
@@ -32,8 +32,10 @@
*
****************************************************************************/
-/*
- * @file Implementation of AR.Drone 1.0 / 2.0 control interface
+/**
+ * @file multirotor_pos_control.c
+ *
+ * Skeleton for multirotor position controller
*/
#include <nuttx/config.h>
diff --git a/apps/px4/tests/test_adc.c b/apps/px4/tests/test_adc.c
index 7795f07ac..c33af1311 100644
--- a/apps/px4/tests/test_adc.c
+++ b/apps/px4/tests/test_adc.c
@@ -1,7 +1,6 @@
/****************************************************************************
- * px4/sensors/test_gpio.c
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -13,7 +12,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
+ * 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -32,9 +31,10 @@
*
****************************************************************************/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+/**
+ * @file test_adc.c
+ * Test for the analog to digital converter.
+ */
#include <nuttx/config.h>
#include <nuttx/arch.h>
@@ -54,91 +54,46 @@
#include <nuttx/analog/adc.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: test_gpio
- ****************************************************************************/
-
int test_adc(int argc, char *argv[])
{
- int fd0;
+ int fd0 = 0;
int ret = 0;
- //struct adc_msg_s sample[4],sample2[4],sample3[4],sample4[4],sample5[4],sample6[4],sample7[4],sample8[4],sample9[4];
+ #pragma pack(push,1)
struct adc_msg4_s {
- uint8_t am_channel1; /* The 8-bit ADC Channel */
- int32_t am_data1; /* ADC convert result (4 bytes) */
- uint8_t am_channel2; /* The 8-bit ADC Channel */
- int32_t am_data2; /* ADC convert result (4 bytes) */
- uint8_t am_channel3; /* The 8-bit ADC Channel */
- int32_t am_data3; /* ADC convert result (4 bytes) */
- uint8_t am_channel4; /* The 8-bit ADC Channel */
- int32_t am_data4; /* ADC convert result (4 bytes) */
- } __attribute__((__packed__));;
-
- struct adc_msg4_s sample1[4], sample2[4];
-
- size_t readsize;
- ssize_t nbytes, nbytes2;
- int i;
+ uint8_t am_channel1; /**< The 8-bit ADC Channel 1 */
+ int32_t am_data1; /**< ADC convert result 1 (4 bytes) */
+ uint8_t am_channel2; /**< The 8-bit ADC Channel 2 */
+ int32_t am_data2; /**< ADC convert result 2 (4 bytes) */
+ uint8_t am_channel3; /**< The 8-bit ADC Channel 3 */
+ int32_t am_data3; /**< ADC convert result 3 (4 bytes) */
+ uint8_t am_channel4; /**< The 8-bit ADC Channel 4 */
+ int32_t am_data4; /**< ADC convert result 4 (4 bytes) */
+ };
+ #pragma pack(pop)
+
+ struct adc_msg4_s sample1;
+
+ ssize_t nbytes;
int j;
int errval;
- for (j = 0; j < 1; j++) {
- char name[11];
- sprintf(name, "/dev/adc%d", j);
- fd0 = open(name, O_RDONLY | O_NONBLOCK);
+ fd0 = open("/dev/adc0", O_RDONLY | O_NONBLOCK);
- if (fd0 < 0) {
- printf("ADC: %s open fail\n", name);
- return ERROR;
+ if (fd0 <= 0) {
+ message("/dev/adc0 open fail: %d\n", errno);
+ return ERROR;
- } else {
- printf("Opened %s successfully\n", name);
- }
+ } else {
+ message("opened /dev/adc0 successfully\n");
+ }
+ usleep(10000);
- /* first adc read round */
- readsize = 4 * sizeof(struct adc_msg_s);
- up_udelay(10000);//microseconds
- nbytes = read(fd0, sample1, readsize);
- up_udelay(10000);//microseconds
- nbytes2 = read(fd0, sample2, readsize);
-// nbytes2 = read(fd0, sample3, readsize);
-// nbytes2 = read(fd0, sample4, readsize);
-// nbytes2 = read(fd0, sample5, readsize);
-// nbytes2 = read(fd0, sample6, readsize);
-// nbytes2 = read(fd0, sample7, readsize);
-// nbytes2 = read(fd0, sample8, readsize);
- //nbytes2 = read(fd0, sample9, readsize);
+ for (j = 0; j < 10; j++) {
+
+ /* sleep 20 milliseconds */
+ usleep(20000);
+ nbytes = read(fd0, &sample1, sizeof(sample1));
/* Handle unexpected return values */
@@ -146,62 +101,44 @@ int test_adc(int argc, char *argv[])
errval = errno;
if (errval != EINTR) {
- message("read %s failed: %d\n",
- name, errval);
+ message("reading /dev/adc0 failed: %d\n", errval);
errval = 3;
goto errout_with_dev;
}
- message("\tInterrupted read...\n");
+ message("\tinterrupted read..\n");
} else if (nbytes == 0) {
- message("\tNo data read, Ignoring\n");
+ message("\tno data read, ignoring.\n");
+ ret = ERROR;
}
/* Print the sample data on successful return */
else {
- int nsamples = nbytes / sizeof(struct adc_msg_s);
-
- if (nsamples * sizeof(struct adc_msg_s) != nbytes) {
- message("\tread size=%d is not a multiple of sample size=%d, Ignoring\n",
- nbytes, sizeof(struct adc_msg_s));
+ if (nbytes != sizeof(sample1)) {
+ message("\tsample 1 size %d is not matching struct size %d, ignoring\n",
+ nbytes, sizeof(sample1));
+ ret = ERROR;
} else {
- message("Sample:");
-
- for (i = 0; i < 1 ; i++) {
- message("%d: channel: %d value: %d\n",
- i, sample1[i].am_channel1, sample1[i].am_data1);
- message("Sample:");
- message("%d: channel: %d value: %d\n",
- i, sample1[i].am_channel2, sample1[i].am_data2);
- message("Sample:");
- message("%d: channel: %d value: %d\n",
- i, sample1[i].am_channel3, sample1[i].am_data3);
- message("Sample:");
- message("%d: channel: %d value: %d\n",
- i, sample1[i].am_channel4, sample1[i].am_data4);
- message("Sample:");
- message("%d: channel: %d value: %d\n",
- i + 1, sample2[i].am_channel1, sample2[i].am_data1);
- message("Sample:");
- message("%d: channel: %d value: %d\n",
- i + 1, sample2[i].am_channel2, sample2[i].am_data2);
- message("Sample:");
- message("%d: channel: %d value: %d\n",
- i + 1, sample2[i].am_channel3, sample2[i].am_data3);
- message("Sample:");
- message("%d: channel: %d value: %d\n",
- i + 1, sample2[i].am_channel4, sample2[i].am_data4);
-// message("%d: channel: %d value: %d\n",
-// i, sample9[i].am_channel, sample9[i].am_data);
- }
+
+ message("CYCLE %d:\n", j);
+
+ message("channel: %d value: %d\n",
+ (int)sample1.am_channel1, sample1.am_data1);
+ message("channel: %d value: %d",
+ (int)sample1.am_channel2, sample1.am_data2);
+ message("channel: %d value: %d",
+ (int)sample1.am_channel3, sample1.am_data3);
+ message("channel: %d value: %d",
+ (int)sample1.am_channel4, sample1.am_data4);
}
}
+ fflush(stdout);
}
- printf("\t ADC test successful.\n");
+ message("\t ADC test successful.");
errout_with_dev:
diff --git a/apps/px4/tests/test_sensors.c b/apps/px4/tests/test_sensors.c
index c801869ab..ad7c74064 100644
--- a/apps/px4/tests/test_sensors.c
+++ b/apps/px4/tests/test_sensors.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,7 +36,7 @@
* @file test_sensors.c
* Tests the onboard sensors.
*
- * The sensors app must not be running when performing this test.
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
@@ -56,7 +56,10 @@
#include "tests.h"
+#include <drivers/drv_gyro.h>
#include <drivers/drv_accel.h>
+#include <drivers/drv_mag.h>
+#include <drivers/drv_baro.h>
/****************************************************************************
* Pre-processor Definitions
@@ -70,8 +73,10 @@
* Private Function Prototypes
****************************************************************************/
-//static int lis331(int argc, char *argv[]);
-static int mpu6000(int argc, char *argv[]);
+static int accel(int argc, char *argv[]);
+static int gyro(int argc, char *argv[]);
+static int mag(int argc, char *argv[]);
+static int baro(int argc, char *argv[]);
/****************************************************************************
* Private Data
@@ -82,7 +87,10 @@ struct {
const char *path;
int (* test)(int argc, char *argv[]);
} sensors[] = {
- {"mpu6000", "/dev/accel", mpu6000},
+ {"accel", "/dev/accel", accel},
+ {"gyro", "/dev/gyro", gyro},
+ {"mag", "/dev/mag", mag},
+ {"baro", "/dev/baro", baro},
{NULL, NULL, NULL}
};
@@ -95,9 +103,9 @@ struct {
****************************************************************************/
static int
-mpu6000(int argc, char *argv[])
+accel(int argc, char *argv[])
{
- printf("\tMPU-6000: test start\n");
+ printf("\tACCEL: test start\n");
fflush(stdout);
int fd;
@@ -107,7 +115,7 @@ mpu6000(int argc, char *argv[])
fd = open("/dev/accel", O_RDONLY);
if (fd < 0) {
- printf("\tMPU-6000: open fail, run <mpu6000 start> first.\n");
+ printf("\tACCEL: open fail, run <mpu6000 start> or <lsm303 start> or <bma180 start> first.\n");
return ERROR;
}
@@ -118,11 +126,11 @@ mpu6000(int argc, char *argv[])
ret = read(fd, &buf, sizeof(buf));
if (ret < 3) {
- printf("\tMPU-6000: read1 fail (%d)\n", ret);
+ printf("\tACCEL: read1 fail (%d)\n", ret);
return ERROR;
} else {
- printf("\tMPU-6000 values: acc: x:%8.4f\ty:%8.4f\tz:%8.4f\n", (double)buf.x, (double)buf.y, (double)buf.z);//\tgyro: r:%d\tp:%d\ty:%d\n", buf[0], buf[1], buf[2], buf[3], buf[4], buf[5]);
+ printf("\tACCEL values: acc: x:%8.4f\ty:%8.4f\tz:%8.4f\n", (double)buf.x, (double)buf.y, (double)buf.z);
}
// /* wait at least 10ms, sensor should have data after no more than 2ms */
@@ -141,7 +149,118 @@ mpu6000(int argc, char *argv[])
/* XXX more tests here */
/* Let user know everything is ok */
- printf("\tOK: MPU-6000 passed all tests successfully\n");
+ printf("\tOK: ACCEL passed all tests successfully\n");
+
+ return OK;
+}
+
+static int
+gyro(int argc, char *argv[])
+{
+ printf("\tGYRO: test start\n");
+ fflush(stdout);
+
+ int fd;
+ struct gyro_report buf;
+ int ret;
+
+ fd = open("/dev/gyro", O_RDONLY);
+
+ if (fd < 0) {
+ printf("\tGYRO: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
+ return ERROR;
+ }
+
+ /* wait at least 5 ms, sensor should have data after that */
+ usleep(5000);
+
+ /* read data - expect samples */
+ ret = read(fd, &buf, sizeof(buf));
+
+ if (ret < 3) {
+ printf("\tGYRO: read fail (%d)\n", ret);
+ return ERROR;
+
+ } else {
+ printf("\tGYRO values: rates: x:%8.4f\ty:%8.4f\tz:%8.4f\n", (double)buf.x, (double)buf.y, (double)buf.z);
+ }
+
+ /* Let user know everything is ok */
+ printf("\tOK: GYRO passed all tests successfully\n");
+
+ return OK;
+}
+
+static int
+mag(int argc, char *argv[])
+{
+ printf("\tMAG: test start\n");
+ fflush(stdout);
+
+ int fd;
+ struct mag_report buf;
+ int ret;
+
+ fd = open("/dev/mag", O_RDONLY);
+
+ if (fd < 0) {
+ printf("\tMAG: open fail, run <hmc5883 start> or <lsm303 start> first.\n");
+ return ERROR;
+ }
+
+ /* wait at least 5 ms, sensor should have data after that */
+ usleep(5000);
+
+ /* read data - expect samples */
+ ret = read(fd, &buf, sizeof(buf));
+
+ if (ret < 3) {
+ printf("\tMAG: read fail (%d)\n", ret);
+ return ERROR;
+
+ } else {
+ printf("\tMAG values: mag. field: x:%8.4f\ty:%8.4f\tz:%8.4f\n", (double)buf.x, (double)buf.y, (double)buf.z);
+ }
+
+ /* Let user know everything is ok */
+ printf("\tOK: MAG passed all tests successfully\n");
+
+ return OK;
+}
+
+static int
+baro(int argc, char *argv[])
+{
+ printf("\tBARO: test start\n");
+ fflush(stdout);
+
+ int fd;
+ struct baro_report buf;
+ int ret;
+
+ fd = open("/dev/baro", O_RDONLY);
+
+ if (fd < 0) {
+ printf("\tBARO: open fail, run <ms5611 start> or <lps331 start> first.\n");
+ return ERROR;
+ }
+
+ /* wait at least 5 ms, sensor should have data after that */
+ usleep(5000);
+
+ /* read data - expect samples */
+ ret = read(fd, &buf, sizeof(buf));
+
+ if (ret < 3) {
+ printf("\tBARO: read fail (%d)\n", ret);
+ return ERROR;
+
+ } else {
+ printf("\tBARO values: pressure: %8.4f mbar\taltitude: %8.4f m\ttemperature: %8.4f deg Celsius\n", (double)buf.pressure, (double)buf.altitude, (double)buf.temperature);
+ }
+
+ /* Let user know everything is ok */
+ printf("\tOK: BARO passed all tests successfully\n");
return OK;
}
diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp
index 3e9f35eaf..675a8602a 100644
--- a/apps/sensors/sensors.cpp
+++ b/apps/sensors/sensors.cpp
@@ -34,9 +34,9 @@
/**
* @file sensors.cpp
- * @author Lorenz Meier <lm@inf.ethz.ch>
- *
* Sensor readout process.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
diff --git a/apps/uORB/topics/subsystem_info.h b/apps/uORB/topics/subsystem_info.h
index 89b397478..c3e039d66 100644
--- a/apps/uORB/topics/subsystem_info.h
+++ b/apps/uORB/topics/subsystem_info.h
@@ -1,9 +1,9 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +37,10 @@
/**
* @file subsystem_info.h
* Definition of the subsystem info topic.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef TOPIC_SUBSYSTEM_INFO_H_