aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xapps/attitude_estimator_ekf/Makefile5
-rwxr-xr-xapps/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp (renamed from apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c)17
-rw-r--r--apps/drivers/blinkm/blinkm.cpp3
-rw-r--r--apps/drivers/gps/ubx.cpp18
-rw-r--r--apps/drivers/stm32/drv_hrt.c2
-rw-r--r--apps/drivers/stm32/tone_alarm/tone_alarm.cpp8
-rw-r--r--apps/examples/kalman_demo/KalmanNav.cpp2
-rw-r--r--apps/examples/nsh/Makefile2
-rw-r--r--apps/mavlink/mavlink_receiver.c14
-rw-r--r--apps/mavlink/orb_listener.c18
-rw-r--r--apps/nshlib/Makefile2
-rw-r--r--apps/px4/tests/Makefile2
-rw-r--r--apps/system/i2c/Makefile1
-rw-r--r--apps/systemcmds/bl_update/Makefile2
-rw-r--r--apps/systemcmds/boardinfo/Makefile2
-rw-r--r--apps/systemcmds/calibration/Makefile2
-rw-r--r--apps/systemcmds/delay_test/Makefile2
-rw-r--r--apps/systemcmds/eeprom/Makefile2
-rw-r--r--apps/systemcmds/mixer/Makefile2
-rw-r--r--apps/systemcmds/param/Makefile2
-rw-r--r--apps/systemcmds/perf/Makefile2
-rw-r--r--apps/systemcmds/preflight_check/Makefile2
-rw-r--r--apps/systemcmds/reboot/Makefile2
-rw-r--r--apps/systemcmds/top/Makefile2
-rw-r--r--apps/uORB/topics/vehicle_gps_position.h39
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h1
-rw-r--r--nuttx/configs/px4io/common/Make.defs3
27 files changed, 109 insertions, 50 deletions
diff --git a/apps/attitude_estimator_ekf/Makefile b/apps/attitude_estimator_ekf/Makefile
index 734af7cc1..46a54c660 100755
--- a/apps/attitude_estimator_ekf/Makefile
+++ b/apps/attitude_estimator_ekf/Makefile
@@ -35,8 +35,9 @@ APPNAME = attitude_estimator_ekf
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
-CSRCS = attitude_estimator_ekf_main.c \
- attitude_estimator_ekf_params.c \
+CXXSRCS = attitude_estimator_ekf_main.cpp
+
+CSRCS = attitude_estimator_ekf_params.c \
codegen/eye.c \
codegen/attitudeKalmanfilter.c \
codegen/mrdivide.c \
diff --git a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index bd972f03f..1a50dde0f 100755
--- a/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.c
+++ b/apps/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -66,11 +66,17 @@
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
+#ifdef __cplusplus
+extern "C" {
+#endif
#include "codegen/attitudeKalmanfilter_initialize.h"
#include "codegen/attitudeKalmanfilter.h"
#include "attitude_estimator_ekf_params.h"
+#ifdef __cplusplus
+}
+#endif
-__EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
+extern "C" __EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
@@ -265,10 +271,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* Main loop*/
while (!thread_should_exit) {
- struct pollfd fds[2] = {
- { .fd = sub_raw, .events = POLLIN },
- { .fd = sub_params, .events = POLLIN }
- };
+ struct pollfd fds[2];
+ fds[0].fd = sub_raw;
+ fds[0].events = POLLIN;
+ fds[1].fd = sub_params;
+ fds[1].events = POLLIN;
int ret = poll(fds, 2, 1000);
if (ret < 0) {
diff --git a/apps/drivers/blinkm/blinkm.cpp b/apps/drivers/blinkm/blinkm.cpp
index 56265995f..3fabfd9a5 100644
--- a/apps/drivers/blinkm/blinkm.cpp
+++ b/apps/drivers/blinkm/blinkm.cpp
@@ -92,6 +92,7 @@
#include <nuttx/config.h>
+#include <arch/board/board.h>
#include <drivers/device/i2c.h>
#include <sys/types.h>
@@ -841,7 +842,7 @@ int
blinkm_main(int argc, char *argv[])
{
- int i2cdevice = 3;
+ int i2cdevice = PX4_I2C_BUS_EXPANSION;
int blinkmadr = 9;
int x;
diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp
index 0d4894b8d..c150f5271 100644
--- a/apps/drivers/gps/ubx.cpp
+++ b/apps/drivers/gps/ubx.cpp
@@ -33,7 +33,14 @@
*
****************************************************************************/
-/* @file U-Blox protocol implementation */
+/**
+ * @file ubx.cpp
+ *
+ * U-Blox protocol implementation. Following u-blox 6/7 Receiver Description
+ * including Prototol Specification.
+ *
+ * @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
+ */
#include <unistd.h>
#include <stdio.h>
@@ -633,16 +640,17 @@ UBX::handle_message()
}
case NAV_VELNED: {
-// printf("GOT NAV_VELNED MESSAGE\n");
if (!_waiting_for_ack) {
+ /* 35.15 NAV-VELNED (0x01 0x12) message (page 181 / 210 of reference manual */
gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
_gps_position->vel_m_s = (float)packet->speed * 1e-2f;
- _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f;
- _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f;
- _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f;
+ _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */
+ _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */
+ _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */
_gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
+ _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f;
_gps_position->vel_ned_valid = true;
_gps_position->timestamp_velocity = hrt_absolute_time();
}
diff --git a/apps/drivers/stm32/drv_hrt.c b/apps/drivers/stm32/drv_hrt.c
index bb67d5e6d..cec0c49ff 100644
--- a/apps/drivers/stm32/drv_hrt.c
+++ b/apps/drivers/stm32/drv_hrt.c
@@ -125,7 +125,7 @@
# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
# if CONFIG_STM32_TIM8
-# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=6
+# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=8
# endif
#elif HRT_TIMER == 9
# define HRT_TIMER_BASE STM32_TIM9_BASE
diff --git a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
index baa652d8a..ac5511e60 100644
--- a/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/apps/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -494,7 +494,7 @@ ToneAlarm::init()
return ret;
/* configure the GPIO to the idle state */
- stm32_configgpio(GPIO_TONE_ALARM);
+ stm32_configgpio(GPIO_TONE_ALARM_IDLE);
/* clock/power on our timer */
modifyreg32(STM32_RCC_APB1ENR, 0, TONE_ALARM_CLOCK_ENABLE);
@@ -606,6 +606,8 @@ ToneAlarm::start_note(unsigned note)
rEGR = GTIM_EGR_UG; // force a reload of the period
rCCER |= TONE_CCER; // enable the output
+ // configure the GPIO to enable timer output
+ stm32_configgpio(GPIO_TONE_ALARM);
}
void
@@ -616,10 +618,8 @@ ToneAlarm::stop_note()
/*
* Make sure the GPIO is not driving the speaker.
- *
- * XXX this presumes PX4FMU and the onboard speaker driver FET.
*/
- stm32_gpiowrite(GPIO_TONE_ALARM, 0);
+ stm32_configgpio(GPIO_TONE_ALARM_IDLE);
}
void
diff --git a/apps/examples/kalman_demo/KalmanNav.cpp b/apps/examples/kalman_demo/KalmanNav.cpp
index 6df454a55..4ef150da1 100644
--- a/apps/examples/kalman_demo/KalmanNav.cpp
+++ b/apps/examples/kalman_demo/KalmanNav.cpp
@@ -355,6 +355,8 @@ int KalmanNav::predictState(float dt)
float LDot = vN / R;
float lDot = vE / (cosLSing * R);
float rotRate = 2 * omega + lDot;
+
+ // XXX position prediction using speed
float vNDot = fN - vE * rotRate * sinL +
vD * LDot;
float vDDot = fD - vE * rotRate * cosL -
diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile
index c7d212fc2..ad687958f 100644
--- a/apps/examples/nsh/Makefile
+++ b/apps/examples/nsh/Makefile
@@ -64,6 +64,8 @@ ROOTDEPPATH = --dep-path .
VPATH =
+MAXOPTIMIZATION = -Os
+
all: .built
.PHONY: clean depend distclean
diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c
index a30f0bf3c..22c2fcdad 100644
--- a/apps/mavlink/mavlink_receiver.c
+++ b/apps/mavlink/mavlink_receiver.c
@@ -477,25 +477,27 @@ handle_message(mavlink_message_t *msg)
/* gps */
hil_gps.timestamp_position = gps.time_usec;
-// hil_gps.counter = hil_counter++;
hil_gps.time_gps_usec = gps.time_usec;
hil_gps.lat = gps.lat;
hil_gps.lon = gps.lon;
hil_gps.alt = gps.alt;
-// hil_gps.counter_pos_valid = hil_counter++;
hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
hil_gps.s_variance_m_s = 5.0f;
hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m;
hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
- /* gps.cog is in degrees 0..360 * 100, heading is -PI..PI */
- float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f - M_PI_F;
+ /* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */
+ float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f;
+ /* go back to -PI..PI */
+ if (heading_rad > M_PI_F)
+ heading_rad -= 2.0f * M_PI_F;
hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(heading_rad);
hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(heading_rad);
hil_gps.vel_d_m_s = 0.0f;
- /* COG (course over ground) is speced as 0..360 degrees (compass) */
- hil_gps.cog_rad = heading_rad + M_PI_F; // from deg*100 to rad
+ hil_gps.vel_ned_valid = true;
+ /* COG (course over ground) is speced as -PI..+PI */
+ hil_gps.cog_rad = heading_rad;
hil_gps.fix_type = gps.fix_type;
hil_gps.satellites_visible = gps.satellites_visible;
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 1dd3fc2d8..5f15facf8 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -229,6 +229,13 @@ l_vehicle_gps_position(const struct listener *l)
/* copy gps data into local buffer */
orb_copy(ORB_ID(vehicle_gps_position), mavlink_subs.gps_sub, &gps);
+ /* GPS COG is 0..2PI in degrees * 1e2 */
+ float cog_deg = gps.cog_rad;
+ if (cog_deg > M_PI_F)
+ cog_deg -= 2.0f * M_PI_F;
+ cog_deg *= M_RAD_TO_DEG_F;
+
+
/* GPS position */
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
gps.timestamp_position,
@@ -236,13 +243,14 @@ l_vehicle_gps_position(const struct listener *l)
gps.lat,
gps.lon,
gps.alt,
- (uint16_t)(gps.eph_m * 1e2f), // from m to cm
- (uint16_t)(gps.epv_m * 1e2f), // from m to cm
- (uint16_t)(gps.vel_m_s * 1e2f), // from m/s to cm/s
- (uint16_t)(gps.cog_rad * M_RAD_TO_DEG_F * 1e2f), // from rad to deg * 100
+ gps.eph_m * 1e2f, // from m to cm
+ gps.epv_m * 1e2f, // from m to cm
+ gps.vel_m_s * 1e2f, // from m/s to cm/s
+ cog_deg * 1e2f, // from rad to deg * 100
gps.satellites_visible);
- if (gps.satellite_info_available && (gps_counter % 4 == 0)) {
+ /* update SAT info every 10 seconds */
+ if (gps.satellite_info_available && (gps_counter % 50 == 0)) {
mavlink_msg_gps_status_send(MAVLINK_COMM_0,
gps.satellites_visible,
gps.satellite_prn,
diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile
index 76cdac40d..4256a1091 100644
--- a/apps/nshlib/Makefile
+++ b/apps/nshlib/Makefile
@@ -107,6 +107,8 @@ endif
ROOTDEPPATH = --dep-path .
VPATH =
+MAXOPTIMIZATION = -Os
+
# Build targets
all: .built
diff --git a/apps/px4/tests/Makefile b/apps/px4/tests/Makefile
index cb1c3c618..34f058be4 100644
--- a/apps/px4/tests/Makefile
+++ b/apps/px4/tests/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 12000
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile
index 1ed7a2fae..c98e2c0e2 100644
--- a/apps/system/i2c/Makefile
+++ b/apps/system/i2c/Makefile
@@ -64,6 +64,7 @@ VPATH =
APPNAME = i2c
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
+MAXOPTIMIZATION = -Os
# Build targets
diff --git a/apps/systemcmds/bl_update/Makefile b/apps/systemcmds/bl_update/Makefile
index 9d0e156f6..d05493577 100644
--- a/apps/systemcmds/bl_update/Makefile
+++ b/apps/systemcmds/bl_update/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/boardinfo/Makefile b/apps/systemcmds/boardinfo/Makefile
index 753a6843e..6f1be149c 100644
--- a/apps/systemcmds/boardinfo/Makefile
+++ b/apps/systemcmds/boardinfo/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/calibration/Makefile b/apps/systemcmds/calibration/Makefile
index aa1aa7761..a1735962e 100644
--- a/apps/systemcmds/calibration/Makefile
+++ b/apps/systemcmds/calibration/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_MAX - 1
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/delay_test/Makefile b/apps/systemcmds/delay_test/Makefile
index d30fcba27..e54cf2f4e 100644
--- a/apps/systemcmds/delay_test/Makefile
+++ b/apps/systemcmds/delay_test/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/eeprom/Makefile b/apps/systemcmds/eeprom/Makefile
index 2f3db0fdc..79a05550e 100644
--- a/apps/systemcmds/eeprom/Makefile
+++ b/apps/systemcmds/eeprom/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/mixer/Makefile b/apps/systemcmds/mixer/Makefile
index b016ddc57..3d8ac38cb 100644
--- a/apps/systemcmds/mixer/Makefile
+++ b/apps/systemcmds/mixer/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/param/Makefile b/apps/systemcmds/param/Makefile
index 603746a20..f19cadbb6 100644
--- a/apps/systemcmds/param/Makefile
+++ b/apps/systemcmds/param/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/perf/Makefile b/apps/systemcmds/perf/Makefile
index 0134c9948..f8bab41b6 100644
--- a/apps/systemcmds/perf/Makefile
+++ b/apps/systemcmds/perf/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/preflight_check/Makefile b/apps/systemcmds/preflight_check/Makefile
index f138e2640..98aadaa86 100644
--- a/apps/systemcmds/preflight_check/Makefile
+++ b/apps/systemcmds/preflight_check/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/reboot/Makefile b/apps/systemcmds/reboot/Makefile
index 9609a24fd..15dd19982 100644
--- a/apps/systemcmds/reboot/Makefile
+++ b/apps/systemcmds/reboot/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/top/Makefile b/apps/systemcmds/top/Makefile
index c45775f4b..f58f9212e 100644
--- a/apps/systemcmds/top/Makefile
+++ b/apps/systemcmds/top/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT - 10
STACKSIZE = 3000
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/uORB/topics/vehicle_gps_position.h b/apps/uORB/topics/vehicle_gps_position.h
index 5463a460d..0a7fb4e9d 100644
--- a/apps/uORB/topics/vehicle_gps_position.h
+++ b/apps/uORB/topics/vehicle_gps_position.h
@@ -55,38 +55,39 @@
*/
struct vehicle_gps_position_s
{
- uint64_t timestamp_position; /**< Timestamp for position information */
- int32_t lat; /**< Latitude in 1E7 degrees */
- int32_t lon; /**< Longitude in 1E7 degrees */
- int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
+ uint64_t timestamp_position; /**< Timestamp for position information */
+ int32_t lat; /**< Latitude in 1E7 degrees */
+ int32_t lon; /**< Longitude in 1E7 degrees */
+ int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
uint64_t timestamp_variance;
float s_variance_m_s; /**< speed accuracy estimate m/s */
- float p_variance_m; /**< position accuracy estimate m */
- uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
+ float p_variance_m; /**< position accuracy estimate m */
+ float c_variance_rad; /**< course accuracy estimate rad */
+ uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
- float eph_m; /**< GPS HDOP horizontal dilution of position in m */
- float epv_m; /**< GPS VDOP horizontal dilution of position in m */
+ float eph_m; /**< GPS HDOP horizontal dilution of position in m */
+ float epv_m; /**< GPS VDOP horizontal dilution of position in m */
- uint64_t timestamp_velocity; /**< Timestamp for velocity informations */
- float vel_m_s; /**< GPS ground speed (m/s) */
- float vel_n_m_s; /**< GPS ground speed in m/s */
- float vel_e_m_s; /**< GPS ground speed in m/s */
- float vel_d_m_s; /**< GPS ground speed in m/s */
- float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad */
- bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */
+ uint64_t timestamp_velocity; /**< Timestamp for velocity informations */
+ float vel_m_s; /**< GPS ground speed (m/s) */
+ float vel_n_m_s; /**< GPS ground speed in m/s */
+ float vel_e_m_s; /**< GPS ground speed in m/s */
+ float vel_d_m_s; /**< GPS ground speed in m/s */
+ float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */
+ bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */
uint64_t timestamp_time; /**< Timestamp for time information */
uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */
- uint64_t timestamp_satellites; /**< Timestamp for sattelite information */
+ uint64_t timestamp_satellites; /**< Timestamp for sattelite information */
uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */
uint8_t satellite_prn[20]; /**< Global satellite ID */
uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
- uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
- uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
+ uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
+ uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */
- bool satellite_info_available; /**< 0 for no info, 1 for info available */
+ bool satellite_info_available; /**< 0 for no info, 1 for info available */
};
/**
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index 8ad56a4c6..0bc0b3021 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -326,6 +326,7 @@
*/
#define TONE_ALARM_TIMER 3 /* timer 3 */
#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
/************************************************************************************
diff --git a/nuttx/configs/px4io/common/Make.defs b/nuttx/configs/px4io/common/Make.defs
index 4958f7092..7f782b5b2 100644
--- a/nuttx/configs/px4io/common/Make.defs
+++ b/nuttx/configs/px4io/common/Make.defs
@@ -112,7 +112,6 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
-ARCHSCRIPT += -g
endif
ARCHCFLAGS = -std=gnu99
@@ -145,7 +144,7 @@ ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
-ARCHSCRIPT += --warn-common \
+EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common