aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-12 16:11:43 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-12 16:11:43 +0200
commita2f528c5ba20ade8c3be200ed07fb6e925030c0d (patch)
tree4b67a981db55183441f553ba967c1faec912e982 /src/drivers
parentee9233451244604f1522dda5e58d1deb7ec6473d (diff)
parent4dc65d6f09bcf891ee228ef9fc6b576251fc8b65 (diff)
downloadpx4-firmware-a2f528c5ba20ade8c3be200ed07fb6e925030c0d.tar.gz
px4-firmware-a2f528c5ba20ade8c3be200ed07fb6e925030c0d.tar.bz2
px4-firmware-a2f528c5ba20ade8c3be200ed07fb6e925030c0d.zip
Merged master
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/device/spi.cpp62
-rw-r--r--src/drivers/device/spi.h2
-rw-r--r--src/drivers/drv_px4flow.h16
-rw-r--r--src/drivers/drv_range_finder.h9
-rw-r--r--src/drivers/drv_rc_input.h9
-rw-r--r--src/drivers/gps/gps.cpp4
-rw-r--r--src/drivers/px4fmu/fmu.cpp2
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp22
8 files changed, 85 insertions, 41 deletions
diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp
index 0b232e158..1ab1dc699 100644
--- a/src/drivers/device/spi.cpp
+++ b/src/drivers/device/spi.cpp
@@ -133,26 +133,44 @@ SPI::probe()
int
SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
{
- irqstate_t state;
+ int result;
if ((send == nullptr) && (recv == nullptr))
return -EINVAL;
+ LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode;
+
/* lock the bus as required */
- if (!up_interrupt_context()) {
- switch (locking_mode) {
- default:
- case LOCK_PREEMPTION:
- state = irqsave();
- break;
- case LOCK_THREADS:
- SPI_LOCK(_dev, true);
- break;
- case LOCK_NONE:
- break;
+ switch (mode) {
+ default:
+ case LOCK_PREEMPTION:
+ {
+ irqstate_t state = irqsave();
+ result = _transfer(send, recv, len);
+ irqrestore(state);
}
+ break;
+ case LOCK_THREADS:
+ SPI_LOCK(_dev, true);
+ result = _transfer(send, recv, len);
+ SPI_LOCK(_dev, false);
+ break;
+ case LOCK_NONE:
+ result = _transfer(send, recv, len);
+ break;
}
+ return result;
+}
+void
+SPI::set_frequency(uint32_t frequency)
+{
+ _frequency = frequency;
+}
+
+int
+SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len)
+{
SPI_SETFREQUENCY(_dev, _frequency);
SPI_SETMODE(_dev, _mode);
SPI_SETBITS(_dev, 8);
@@ -164,27 +182,7 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len)
/* and clean up */
SPI_SELECT(_dev, _device, false);
- if (!up_interrupt_context()) {
- switch (locking_mode) {
- default:
- case LOCK_PREEMPTION:
- irqrestore(state);
- break;
- case LOCK_THREADS:
- SPI_LOCK(_dev, false);
- break;
- case LOCK_NONE:
- break;
- }
- }
-
return OK;
}
-void
-SPI::set_frequency(uint32_t frequency)
-{
- _frequency = frequency;
-}
-
} // namespace device
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index 03986da1e..54849c8c3 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -131,6 +131,8 @@ private:
protected:
int _bus;
+
+ int _transfer(uint8_t *send, uint8_t *recv, unsigned len);
};
} // namespace device
diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h
index bef02d54e..76ec55c3e 100644
--- a/src/drivers/drv_px4flow.h
+++ b/src/drivers/drv_px4flow.h
@@ -47,9 +47,17 @@
#define PX4FLOW_DEVICE_PATH "/dev/px4flow"
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Optical flow in NED body frame in SI units.
*
* @see http://en.wikipedia.org/wiki/International_System_of_Units
+ *
+ * @warning If possible the usage of the raw flow and performing rotation-compensation
+ * using the autopilot angular rate estimate is recommended.
*/
struct px4flow_report {
@@ -57,14 +65,18 @@ struct px4flow_report {
int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
- float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
- float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
+ float flow_comp_x_m; /**< speed over ground in meters per second, rotation-compensated */
+ float flow_comp_y_m; /**< speed over ground in meters per second, rotation-compensated */
float ground_distance_m; /**< Altitude / distance to ground in meters */
uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
uint8_t sensor_id; /**< id of the sensor emitting the flow value */
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for px4flow data.
*/
diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h
index e45939b37..0f8362f58 100644
--- a/src/drivers/drv_range_finder.h
+++ b/src/drivers/drv_range_finder.h
@@ -51,6 +51,11 @@ enum RANGE_FINDER_TYPE {
};
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* range finder report structure. Reads from the device must be in multiples of this
* structure.
*/
@@ -64,6 +69,10 @@ struct range_finder_report {
uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for raw range finder data.
*/
diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h
index 20763e265..47fa8fa59 100644
--- a/src/drivers/drv_rc_input.h
+++ b/src/drivers/drv_rc_input.h
@@ -68,6 +68,11 @@
#define RC_INPUT_RSSI_MAX 255
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Input signal type, value is a control position from zero to 100
* percent.
*/
@@ -141,6 +146,10 @@ struct rc_input_values {
rc_input_t values[RC_INPUT_MAX_CHANNELS];
};
+/**
+ * @}
+ */
+
/*
* ObjDev tag for R/C inputs.
*/
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 401b65dd4..34dd63086 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -127,7 +127,7 @@ private:
/**
* Try to configure the GPS, handle outgoing communication to the GPS
*/
- void config();
+ void config();
/**
* Trampoline to the worker task
@@ -486,6 +486,8 @@ GPS::print_info()
warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type,
_report_gps_pos.satellites_used, (double)(hrt_absolute_time() - _report_gps_pos.timestamp_position) / 1000.0);
warnx("lat: %d, lon: %d, alt: %d", _report_gps_pos.lat, _report_gps_pos.lon, _report_gps_pos.alt);
+ warnx("vel: %.2fm/s, %.2fm/s, %.2fm/s", (double)_report_gps_pos.vel_n_m_s,
+ (double)_report_gps_pos.vel_e_m_s, (double)_report_gps_pos.vel_d_m_s);
warnx("eph: %.2fm, epv: %.2fm", (double)_report_gps_pos.eph, (double)_report_gps_pos.epv);
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 39cc32967..8cc1141aa 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -329,7 +329,7 @@ PX4FMU::init()
_task = task_spawn_cmd("fmuservo",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1600,
(main_t)&PX4FMU::task_main_trampoline,
nullptr);
diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index 7b6361a7c..d134c0246 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
@@ -413,11 +414,17 @@ static int read_with_retry(int fd, void *buf, size_t n)
int
PX4IO_Uploader::program(size_t fw_size)
{
- uint8_t file_buf[PROG_MULTI_MAX];
+ uint8_t *file_buf;
ssize_t count;
int ret;
size_t sent = 0;
+ file_buf = (uint8_t *)malloc(PROG_MULTI_MAX);
+ if (!file_buf) {
+ log("Can't allocate program buffer");
+ return -ENOMEM;
+ }
+
log("programming %u bytes...", (unsigned)fw_size);
ret = lseek(_fw_fd, 0, SEEK_SET);
@@ -425,8 +432,8 @@ PX4IO_Uploader::program(size_t fw_size)
while (sent < fw_size) {
/* get more bytes to program */
size_t n = fw_size - sent;
- if (n > sizeof(file_buf)) {
- n = sizeof(file_buf);
+ if (n > PROG_MULTI_MAX) {
+ n = PROG_MULTI_MAX;
}
count = read_with_retry(_fw_fd, file_buf, n);
@@ -438,8 +445,10 @@ PX4IO_Uploader::program(size_t fw_size)
(int)errno);
}
- if (count == 0)
+ if (count == 0) {
+ free(file_buf);
return OK;
+ }
sent += count;
@@ -455,9 +464,12 @@ PX4IO_Uploader::program(size_t fw_size)
ret = get_sync(1000);
- if (ret != OK)
+ if (ret != OK) {
+ free(file_buf);
return ret;
+ }
}
+ free(file_buf);
return OK;
}