mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-04 21:23:57 +08:00
Merge branch 'master' of https://github.com/PX4/Firmware into fw_control
This commit is contained in:
@@ -1,7 +1,7 @@
|
|||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
* 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
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -35,6 +35,8 @@
|
|||||||
/**
|
/**
|
||||||
* @file mavlink_receiver.c
|
* @file mavlink_receiver.c
|
||||||
* MAVLink protocol message receive and dispatch
|
* MAVLink protocol message receive and dispatch
|
||||||
|
*
|
||||||
|
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* XXX trim includes */
|
/* XXX trim includes */
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
* 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
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -35,6 +35,8 @@
|
|||||||
/**
|
/**
|
||||||
* @file orb_listener.c
|
* @file orb_listener.c
|
||||||
* Monitors ORB topics and sends update messages as appropriate.
|
* Monitors ORB topics and sends update messages as appropriate.
|
||||||
|
*
|
||||||
|
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// XXX trim includes
|
// XXX trim includes
|
||||||
|
|||||||
@@ -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>
|
#include <nuttx/config.h>
|
||||||
|
|||||||
+53
-116
@@ -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
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -13,7 +12,7 @@
|
|||||||
* notice, this list of conditions and the following disclaimer in
|
* notice, this list of conditions and the following disclaimer in
|
||||||
* the documentation and/or other materials provided with the
|
* the documentation and/or other materials provided with the
|
||||||
* distribution.
|
* 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
|
* used to endorse or promote products derived from this software
|
||||||
* without specific prior written permission.
|
* 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/config.h>
|
||||||
#include <nuttx/arch.h>
|
#include <nuttx/arch.h>
|
||||||
@@ -54,91 +54,46 @@
|
|||||||
|
|
||||||
#include <nuttx/analog/adc.h>
|
#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 test_adc(int argc, char *argv[])
|
||||||
{
|
{
|
||||||
int fd0;
|
int fd0 = 0;
|
||||||
int ret = 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 {
|
struct adc_msg4_s {
|
||||||
uint8_t am_channel1; /* The 8-bit ADC Channel */
|
uint8_t am_channel1; /**< The 8-bit ADC Channel 1 */
|
||||||
int32_t am_data1; /* ADC convert result (4 bytes) */
|
int32_t am_data1; /**< ADC convert result 1 (4 bytes) */
|
||||||
uint8_t am_channel2; /* The 8-bit ADC Channel */
|
uint8_t am_channel2; /**< The 8-bit ADC Channel 2 */
|
||||||
int32_t am_data2; /* ADC convert result (4 bytes) */
|
int32_t am_data2; /**< ADC convert result 2 (4 bytes) */
|
||||||
uint8_t am_channel3; /* The 8-bit ADC Channel */
|
uint8_t am_channel3; /**< The 8-bit ADC Channel 3 */
|
||||||
int32_t am_data3; /* ADC convert result (4 bytes) */
|
int32_t am_data3; /**< ADC convert result 3 (4 bytes) */
|
||||||
uint8_t am_channel4; /* The 8-bit ADC Channel */
|
uint8_t am_channel4; /**< The 8-bit ADC Channel 4 */
|
||||||
int32_t am_data4; /* ADC convert result (4 bytes) */
|
int32_t am_data4; /**< ADC convert result 4 (4 bytes) */
|
||||||
} __attribute__((__packed__));;
|
};
|
||||||
|
#pragma pack(pop)
|
||||||
|
|
||||||
struct adc_msg4_s sample1[4], sample2[4];
|
struct adc_msg4_s sample1;
|
||||||
|
|
||||||
size_t readsize;
|
ssize_t nbytes;
|
||||||
ssize_t nbytes, nbytes2;
|
|
||||||
int i;
|
|
||||||
int j;
|
int j;
|
||||||
int errval;
|
int errval;
|
||||||
|
|
||||||
for (j = 0; j < 1; j++) {
|
fd0 = open("/dev/adc0", O_RDONLY | O_NONBLOCK);
|
||||||
char name[11];
|
|
||||||
sprintf(name, "/dev/adc%d", j);
|
|
||||||
fd0 = open(name, O_RDONLY | O_NONBLOCK);
|
|
||||||
|
|
||||||
if (fd0 < 0) {
|
if (fd0 <= 0) {
|
||||||
printf("ADC: %s open fail\n", name);
|
message("/dev/adc0 open fail: %d\n", errno);
|
||||||
return ERROR;
|
return ERROR;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
printf("Opened %s successfully\n", name);
|
message("opened /dev/adc0 successfully\n");
|
||||||
}
|
}
|
||||||
|
usleep(10000);
|
||||||
|
|
||||||
/* first adc read round */
|
for (j = 0; j < 10; j++) {
|
||||||
readsize = 4 * sizeof(struct adc_msg_s);
|
|
||||||
up_udelay(10000);//microseconds
|
/* sleep 20 milliseconds */
|
||||||
nbytes = read(fd0, sample1, readsize);
|
usleep(20000);
|
||||||
up_udelay(10000);//microseconds
|
nbytes = read(fd0, &sample1, sizeof(sample1));
|
||||||
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);
|
|
||||||
|
|
||||||
/* Handle unexpected return values */
|
/* Handle unexpected return values */
|
||||||
|
|
||||||
@@ -146,62 +101,44 @@ int test_adc(int argc, char *argv[])
|
|||||||
errval = errno;
|
errval = errno;
|
||||||
|
|
||||||
if (errval != EINTR) {
|
if (errval != EINTR) {
|
||||||
message("read %s failed: %d\n",
|
message("reading /dev/adc0 failed: %d\n", errval);
|
||||||
name, errval);
|
|
||||||
errval = 3;
|
errval = 3;
|
||||||
goto errout_with_dev;
|
goto errout_with_dev;
|
||||||
}
|
}
|
||||||
|
|
||||||
message("\tInterrupted read...\n");
|
message("\tinterrupted read..\n");
|
||||||
|
|
||||||
} else if (nbytes == 0) {
|
} 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 */
|
/* Print the sample data on successful return */
|
||||||
|
|
||||||
else {
|
else {
|
||||||
int nsamples = nbytes / sizeof(struct adc_msg_s);
|
if (nbytes != sizeof(sample1)) {
|
||||||
|
message("\tsample 1 size %d is not matching struct size %d, ignoring\n",
|
||||||
if (nsamples * sizeof(struct adc_msg_s) != nbytes) {
|
nbytes, sizeof(sample1));
|
||||||
message("\tread size=%d is not a multiple of sample size=%d, Ignoring\n",
|
ret = ERROR;
|
||||||
nbytes, sizeof(struct adc_msg_s));
|
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
message("Sample:");
|
|
||||||
|
|
||||||
for (i = 0; i < 1 ; i++) {
|
message("CYCLE %d:\n", j);
|
||||||
message("%d: channel: %d value: %d\n",
|
|
||||||
i, sample1[i].am_channel1, sample1[i].am_data1);
|
message("channel: %d value: %d\n",
|
||||||
message("Sample:");
|
(int)sample1.am_channel1, sample1.am_data1);
|
||||||
message("%d: channel: %d value: %d\n",
|
message("channel: %d value: %d",
|
||||||
i, sample1[i].am_channel2, sample1[i].am_data2);
|
(int)sample1.am_channel2, sample1.am_data2);
|
||||||
message("Sample:");
|
message("channel: %d value: %d",
|
||||||
message("%d: channel: %d value: %d\n",
|
(int)sample1.am_channel3, sample1.am_data3);
|
||||||
i, sample1[i].am_channel3, sample1[i].am_data3);
|
message("channel: %d value: %d",
|
||||||
message("Sample:");
|
(int)sample1.am_channel4, sample1.am_data4);
|
||||||
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);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
fflush(stdout);
|
||||||
}
|
}
|
||||||
|
|
||||||
printf("\t ADC test successful.\n");
|
message("\t ADC test successful.");
|
||||||
|
|
||||||
errout_with_dev:
|
errout_with_dev:
|
||||||
|
|
||||||
|
|||||||
+130
-11
@@ -1,7 +1,7 @@
|
|||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
* 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
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -36,7 +36,7 @@
|
|||||||
* @file test_sensors.c
|
* @file test_sensors.c
|
||||||
* Tests the onboard sensors.
|
* 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>
|
#include <nuttx/config.h>
|
||||||
@@ -56,7 +56,10 @@
|
|||||||
|
|
||||||
#include "tests.h"
|
#include "tests.h"
|
||||||
|
|
||||||
|
#include <drivers/drv_gyro.h>
|
||||||
#include <drivers/drv_accel.h>
|
#include <drivers/drv_accel.h>
|
||||||
|
#include <drivers/drv_mag.h>
|
||||||
|
#include <drivers/drv_baro.h>
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* Pre-processor Definitions
|
* Pre-processor Definitions
|
||||||
@@ -70,8 +73,10 @@
|
|||||||
* Private Function Prototypes
|
* Private Function Prototypes
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
//static int lis331(int argc, char *argv[]);
|
static int accel(int argc, char *argv[]);
|
||||||
static int mpu6000(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
|
* Private Data
|
||||||
@@ -82,7 +87,10 @@ struct {
|
|||||||
const char *path;
|
const char *path;
|
||||||
int (* test)(int argc, char *argv[]);
|
int (* test)(int argc, char *argv[]);
|
||||||
} sensors[] = {
|
} sensors[] = {
|
||||||
{"mpu6000", "/dev/accel", mpu6000},
|
{"accel", "/dev/accel", accel},
|
||||||
|
{"gyro", "/dev/gyro", gyro},
|
||||||
|
{"mag", "/dev/mag", mag},
|
||||||
|
{"baro", "/dev/baro", baro},
|
||||||
{NULL, NULL, NULL}
|
{NULL, NULL, NULL}
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -95,9 +103,9 @@ struct {
|
|||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
static int
|
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);
|
fflush(stdout);
|
||||||
|
|
||||||
int fd;
|
int fd;
|
||||||
@@ -107,7 +115,7 @@ mpu6000(int argc, char *argv[])
|
|||||||
fd = open("/dev/accel", O_RDONLY);
|
fd = open("/dev/accel", O_RDONLY);
|
||||||
|
|
||||||
if (fd < 0) {
|
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;
|
return ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -118,11 +126,11 @@ mpu6000(int argc, char *argv[])
|
|||||||
ret = read(fd, &buf, sizeof(buf));
|
ret = read(fd, &buf, sizeof(buf));
|
||||||
|
|
||||||
if (ret < 3) {
|
if (ret < 3) {
|
||||||
printf("\tMPU-6000: read1 fail (%d)\n", ret);
|
printf("\tACCEL: read1 fail (%d)\n", ret);
|
||||||
return ERROR;
|
return ERROR;
|
||||||
|
|
||||||
} else {
|
} 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 */
|
// /* 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 */
|
/* XXX more tests here */
|
||||||
|
|
||||||
/* Let user know everything is ok */
|
/* 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;
|
return OK;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -34,9 +34,9 @@
|
|||||||
|
|
||||||
/**
|
/**
|
||||||
* @file sensors.cpp
|
* @file sensors.cpp
|
||||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
|
||||||
*
|
|
||||||
* Sensor readout process.
|
* Sensor readout process.
|
||||||
|
*
|
||||||
|
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <nuttx/config.h>
|
#include <nuttx/config.h>
|
||||||
|
|||||||
@@ -1,9 +1,9 @@
|
|||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
*
|
*
|
||||||
* Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
|
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||||
* Author: @author Lorenz Meier <lm@inf.ethz.ch>
|
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||||
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
|
* Thomas Gubler <thomasgubler@student.ethz.ch>
|
||||||
* @author Julian Oes <joes@student.ethz.ch>
|
* Julian Oes <joes@student.ethz.ch>
|
||||||
*
|
*
|
||||||
* Redistribution and use in source and binary forms, with or without
|
* Redistribution and use in source and binary forms, with or without
|
||||||
* modification, are permitted provided that the following conditions
|
* modification, are permitted provided that the following conditions
|
||||||
@@ -37,6 +37,10 @@
|
|||||||
/**
|
/**
|
||||||
* @file subsystem_info.h
|
* @file subsystem_info.h
|
||||||
* Definition of the subsystem info topic.
|
* 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_
|
#ifndef TOPIC_SUBSYSTEM_INFO_H_
|
||||||
|
|||||||
Reference in New Issue
Block a user