aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-05-17 12:36:29 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-05-17 12:36:29 +0200
commit2360bf05bce43dd66a63599530b1bca9fd971b5e (patch)
tree60e19933b54818b01d2234610990f2d01c9d4bf5 /src/modules
parent69bbe4bcb31b0d65caf8532e9d3bd511e790da45 (diff)
parent32ae2dd1d094f4554f5acdad8fb76ed9eb3ba1f0 (diff)
downloadpx4-firmware-2360bf05bce43dd66a63599530b1bca9fd971b5e.tar.gz
px4-firmware-2360bf05bce43dd66a63599530b1bca9fd971b5e.tar.bz2
px4-firmware-2360bf05bce43dd66a63599530b1bca9fd971b5e.zip
Merge remote-tracking branch 'upstream/master' into mtecs
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp1
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp (renamed from src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_main.cpp)16
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c (renamed from src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_params.c)2
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk6
-rw-r--r--src/modules/mavlink/mavlink_main.cpp2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp2
-rw-r--r--src/modules/position_estimator_inav/module.mk2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c2
-rw-r--r--src/modules/px4iofirmware/protocol.h13
-rw-r--r--src/modules/px4iofirmware/registers.c24
10 files changed, 45 insertions, 25 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 13da27dcd..504696ff9 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1710,6 +1710,7 @@ set_control_mode()
case MAIN_STATE_AUTO:
navigator_enabled = true;
+ break;
default:
break;
diff --git a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index 907f4c2e1..7a71894ed 100644
--- a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file fw_att_pos_estimator_main.cpp
+ * @file ekf_att_pos_estimator_main.cpp
* Implementation of the attitude and position estimator.
*
* @author Paul Riseborough <p_riseborough@live.com.au>
@@ -336,13 +336,13 @@ FixedwingEstimator::FixedwingEstimator() :
_baro_gps_offset(0.0f),
/* performance counters */
- _loop_perf(perf_alloc(PC_COUNT, "fw_att_pos_estimator")),
- _perf_gyro(perf_alloc(PC_COUNT, "fw_ekf_gyro_upd")),
- _perf_accel(perf_alloc(PC_COUNT, "fw_ekf_accel_upd")),
- _perf_mag(perf_alloc(PC_COUNT, "fw_ekf_mag_upd")),
- _perf_gps(perf_alloc(PC_COUNT, "fw_ekf_gps_upd")),
- _perf_baro(perf_alloc(PC_COUNT, "fw_ekf_baro_upd")),
- _perf_airspeed(perf_alloc(PC_COUNT, "fw_ekf_aspd_upd")),
+ _loop_perf(perf_alloc(PC_COUNT, "ekf_att_pos_estimator")),
+ _perf_gyro(perf_alloc(PC_COUNT, "ekf_att_pos_gyro_upd")),
+ _perf_accel(perf_alloc(PC_COUNT, "ekf_att_pos_accel_upd")),
+ _perf_mag(perf_alloc(PC_COUNT, "ekf_att_pos_mag_upd")),
+ _perf_gps(perf_alloc(PC_COUNT, "ekf_att_pos_gps_upd")),
+ _perf_baro(perf_alloc(PC_COUNT, "ekf_att_pos_baro_upd")),
+ _perf_airspeed(perf_alloc(PC_COUNT, "ekf_att_pos_aspd_upd")),
/* states */
_initialized(false),
diff --git a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_params.c b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
index d2c6e1f15..1d9ae4623 100644
--- a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_params.c
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file fw_att_pos_estimator_params.c
+ * @file ekf_att_pos_estimator_params.c
*
* Parameters defined by the attitude and position estimator task
*
diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index 30955d0dd..6fefec2c2 100644
--- a/src/modules/ekf_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -32,11 +32,11 @@
############################################################################
#
-# Main Attitude and Position Estimator for Fixed Wing Aircraft
+# Main EKF Attitude and Position Estimator
#
MODULE_COMMAND = ekf_att_pos_estimator
-SRCS = fw_att_pos_estimator_main.cpp \
- fw_att_pos_estimator_params.c \
+SRCS = ekf_att_pos_estimator_main.cpp \
+ ekf_att_pos_estimator_params.c \
estimator.cpp
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 199e85305..6c97bfca7 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -2204,7 +2204,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2000,
+ 1950,
(main_t)&Mavlink::start_helper,
(const char **)argv);
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index b03a68c07..72b9ee83a 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -949,7 +949,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 3000);
+ pthread_attr_setstacksize(&receiveloop_attr, 2900);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);
diff --git a/src/modules/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
index 939d76849..0658d3f09 100644
--- a/src/modules/position_estimator_inav/module.mk
+++ b/src/modules/position_estimator_inav/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = position_estimator_inav
SRCS = position_estimator_inav_main.c \
position_estimator_inav_params.c \
inertial_filter.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 368424853..d8d0ff37d 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -135,7 +135,7 @@ int position_estimator_inav_main(int argc, char *argv[])
thread_should_exit = false;
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
- SCHED_RR, SCHED_PRIORITY_MAX - 5, 4096,
+ SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4000,
position_estimator_inav_thread_main,
(argv) ? (const char **) &argv[2] : (const char **) NULL);
exit(0);
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 91975f2a0..7471faec7 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -190,6 +190,8 @@
#define PX4IO_P_SETUP_RELAYS_POWER2 (1<<1) /* hardware rev [1] power relay 2 */
#define PX4IO_P_SETUP_RELAYS_ACC1 (1<<2) /* hardware rev [1] accessory power 1 */
#define PX4IO_P_SETUP_RELAYS_ACC2 (1<<3) /* hardware rev [1] accessory power 2 */
+#else
+#define PX4IO_P_SETUP_RELAYS_PAD 5
#endif
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* hardware rev [1] battery voltage correction factor (float) */
@@ -209,15 +211,16 @@ enum { /* DSM bind states */
#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
- /* 12 occupied by CRC */
+ /* storage space of 12 occupied by CRC */
+#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
+ 'armed' (PWM enabled) state - this is a non-data write and
+ hence index 12 can safely be used. */
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
-#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
- 'armed' (PWM enabled) state */
-#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
+#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
/* autopilot control values, -10000..10000 */
-#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
+#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index fd7c6081f..db1836f4a 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -160,6 +160,9 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_PWM_ALTRATE] = 200,
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
[PX4IO_P_SETUP_RELAYS] = 0,
+#else
+ /* this is unused, but we will pad it for readability (the compiler pads it automatically) */
+ [PX4IO_P_SETUP_RELAYS_PAD] = 0,
#endif
#ifdef ADC_VSERVO
[PX4IO_P_SETUP_VSERVO_SCALE] = 10000,
@@ -523,18 +526,22 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
break;
case PX4IO_P_SETUP_PWM_DEFAULTRATE:
- if (value < 50)
+ if (value < 50) {
value = 50;
- if (value > 400)
+ }
+ if (value > 400) {
value = 400;
+ }
pwm_configure_rates(r_setup_pwm_rates, value, r_setup_pwm_altrate);
break;
case PX4IO_P_SETUP_PWM_ALTRATE:
- if (value < 50)
+ if (value < 50) {
value = 50;
- if (value > 400)
+ }
+ if (value > 400) {
value = 400;
+ }
pwm_configure_rates(r_setup_pwm_rates, r_setup_pwm_defaultrate, value);
break;
@@ -566,8 +573,9 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
}
// check the magic value
- if (value != PX4IO_REBOOT_BL_MAGIC)
+ if (value != PX4IO_REBOOT_BL_MAGIC) {
break;
+ }
// we schedule a reboot rather than rebooting
// immediately to allow the IO board to ACK
@@ -585,6 +593,12 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
}
break;
+ case PX4IO_P_SETUP_RC_THR_FAILSAFE_US:
+ if (value > 650 && value < 2350) {
+ r_page_setup[PX4IO_P_SETUP_RC_THR_FAILSAFE_US] = value;
+ }
+ break;
+
default:
return -1;
}