aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-06-06 07:57:31 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-06-06 07:57:31 +0200
commit8ad3aa315f09c32cc3e1a85e89f8f6bb9017676c (patch)
treea8f0c7e23f5d64c715cfeade003fd878e3ef027a /src/modules
parent971e8103014412d8453b010063318cf46e996288 (diff)
parent68931f38d56c82c67d7d01e4db3157fac5815258 (diff)
downloadpx4-firmware-8ad3aa315f09c32cc3e1a85e89f8f6bb9017676c.tar.gz
px4-firmware-8ad3aa315f09c32cc3e1a85e89f8f6bb9017676c.tar.bz2
px4-firmware-8ad3aa315f09c32cc3e1a85e89f8f6bb9017676c.zip
Merged master
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.cpp4
-rw-r--r--src/modules/gpio_led/gpio_led.c70
-rw-r--r--src/modules/px4iofirmware/mixer.cpp66
-rw-r--r--src/modules/px4iofirmware/protocol.h4
-rw-r--r--src/modules/px4iofirmware/registers.c10
-rw-r--r--src/modules/systemlib/geo/geo.c5
-rw-r--r--src/modules/systemlib/geo/geo.h16
7 files changed, 140 insertions, 35 deletions
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
index 4ef150da1..c3836bdfa 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
@@ -683,7 +683,8 @@ int KalmanNav::correctPos()
// fault detetcion
float beta = y.dot(S.inverse() * y);
- if (beta > _faultPos.get()) {
+ static int counter = 0;
+ if (beta > _faultPos.get() && (counter % 10 == 0)) {
printf("fault in gps: beta = %8.4f\n", (double)beta);
printf("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f\n",
double(y(0) / sqrtf(RPos(0, 0))),
@@ -693,6 +694,7 @@ int KalmanNav::correctPos()
double(y(4) / sqrtf(RPos(4, 4))),
double(y(5) / sqrtf(RPos(5, 5))));
}
+ counter++;
return ret_ok;
}
diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index a80bf9cb8..43cbe74c7 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -48,6 +48,7 @@
#include <nuttx/wqueue.h>
#include <nuttx/clock.h>
#include <systemlib/systemlib.h>
+#include <systemlib/err.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <poll.h>
@@ -64,6 +65,7 @@ struct gpio_led_s {
};
static struct gpio_led_s gpio_led_data;
+static bool gpio_led_started = false;
__EXPORT int gpio_led_main(int argc, char *argv[]);
@@ -75,31 +77,54 @@ int gpio_led_main(int argc, char *argv[])
{
int pin = GPIO_EXT_1;
- if (argc > 1) {
- if (!strcmp(argv[1], "-p")) {
- if (!strcmp(argv[2], "1")) {
- pin = GPIO_EXT_1;
+ if (argc < 2) {
+ errx(1, "no argument provided. Try 'start' or 'stop' [-p 1/2]");
- } else if (!strcmp(argv[2], "2")) {
- pin = GPIO_EXT_2;
+ } else {
- } else {
- printf("[gpio_led] Unsupported pin: %s\n", argv[2]);
+ /* START COMMAND HANDLING */
+ if (!strcmp(argv[1], "start")) {
+
+ if (argc > 2) {
+ if (!strcmp(argv[1], "-p")) {
+ if (!strcmp(argv[2], "1")) {
+ pin = GPIO_EXT_1;
+
+ } else if (!strcmp(argv[2], "2")) {
+ pin = GPIO_EXT_2;
+
+ } else {
+ warnx("[gpio_led] Unsupported pin: %s\n", argv[2]);
+ exit(1);
+ }
+ }
+ }
+
+ memset(&gpio_led_data, 0, sizeof(gpio_led_data));
+ gpio_led_data.pin = pin;
+ int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0);
+
+ if (ret != 0) {
+ warnx("[gpio_led] Failed to queue work: %d\n", ret);
exit(1);
+
+ } else {
+ gpio_led_started = true;
}
- }
- }
- memset(&gpio_led_data, 0, sizeof(gpio_led_data));
- gpio_led_data.pin = pin;
- int ret = work_queue(LPWORK, &gpio_led_data.work, gpio_led_start, &gpio_led_data, 0);
+ exit(0);
- if (ret != 0) {
- printf("[gpio_led] Failed to queue work: %d\n", ret);
- exit(1);
- }
+ /* STOP COMMAND HANDLING */
+
+ } else if (!strcmp(argv[1], "stop")) {
+ gpio_led_started = false;
- exit(0);
+ /* INVALID COMMAND */
+
+ } else {
+ errx(1, "unrecognized command '%s', only supporting 'start' or 'stop'", argv[1]);
+ }
+ }
}
void gpio_led_start(FAR void *arg)
@@ -110,7 +135,7 @@ void gpio_led_start(FAR void *arg)
priv->gpio_fd = open(GPIO_DEVICE_PATH, 0);
if (priv->gpio_fd < 0) {
- printf("[gpio_led] GPIO: open fail\n");
+ warnx("[gpio_led] GPIO: open fail\n");
return;
}
@@ -125,11 +150,11 @@ void gpio_led_start(FAR void *arg)
int ret = work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, 0);
if (ret != 0) {
- printf("[gpio_led] Failed to queue work: %d\n", ret);
+ warnx("[gpio_led] Failed to queue work: %d\n", ret);
return;
}
- printf("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin);
+ warnx("[gpio_led] Started, using pin GPIO_EXT%i\n", priv->pin);
}
void gpio_led_cycle(FAR void *arg)
@@ -187,5 +212,6 @@ void gpio_led_cycle(FAR void *arg)
priv->counter = 0;
/* repeat cycle at 5 Hz*/
- work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000));
+ if (gpio_led_started)
+ work_queue(LPWORK, &priv->work, gpio_led_cycle, priv, USEC2TICK(200000));
}
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 1234e2eea..0b8ed6dc5 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -85,6 +85,9 @@ static int mixer_callback(uintptr_t handle,
static MixerGroup mixer_group(mixer_callback, 0);
+/* Set the failsafe values of all mixed channels (based on zero throttle, controls centered) */
+static void mixer_set_failsafe();
+
void
mixer_tick(void)
{
@@ -102,13 +105,16 @@ mixer_tick(void)
r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK;
}
+ /* default to failsafe mixing */
source = MIX_FAILSAFE;
/*
* Decide which set of controls we're using.
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ||
- !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
+
+ /* do not mix if mixer is invalid or if RAW_PWM mode is on and FMU is good */
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) &&
+ !(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
/* don't actually mix anything - we already have raw PWM values or
not a valid mixer. */
@@ -117,6 +123,7 @@ mixer_tick(void)
} else {
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) &&
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) &&
(r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) {
/* mix from FMU controls */
@@ -133,14 +140,28 @@ mixer_tick(void)
}
/*
+ * Set failsafe status flag depending on mixing source
+ */
+ if (source == MIX_FAILSAFE) {
+ r_status_flags |= PX4IO_P_STATUS_FLAGS_FAILSAFE;
+ } else {
+ r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_FAILSAFE);
+ }
+
+ /*
* Run the mixers.
*/
if (source == MIX_FAILSAFE) {
/* copy failsafe values to the servo outputs */
- for (unsigned i = 0; i < IO_SERVO_COUNT; i++)
+ for (unsigned i = 0; i < IO_SERVO_COUNT; i++) {
r_page_servos[i] = r_page_servo_failsafe[i];
+ /* safe actuators for FMU feedback */
+ r_page_actuators[i] = (r_page_servos[i] - 1500) / 600.0f;
+ }
+
+
} else if (source != MIX_NONE) {
float outputs[IO_SERVO_COUNT];
@@ -156,7 +177,7 @@ mixer_tick(void)
r_page_actuators[i] = FLOAT_TO_REG(outputs[i]);
/* scale to servo output */
- r_page_servos[i] = (outputs[i] * 500.0f) + 1500;
+ r_page_servos[i] = (outputs[i] * 600.0f) + 1500;
}
for (unsigned i = mixed; i < IO_SERVO_COUNT; i++)
@@ -175,7 +196,7 @@ mixer_tick(void)
bool should_arm = (
/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) &&
/* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) &&
- /* there is valid input */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) &&
+ /* there is valid input via direct PWM or mixer */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) &&
/* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) &&
/* FMU is available or FMU is not available but override is an option */
((r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) || (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) && (r_setup_arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ))
@@ -225,7 +246,7 @@ mixer_callback(uintptr_t handle,
case MIX_FAILSAFE:
case MIX_NONE:
- /* XXX we could allow for configuration of per-output failsafe values */
+ control = 0.0f;
return -1;
}
@@ -303,8 +324,41 @@ mixer_handle_text(const void *buffer, size_t length)
memcpy(&mixer_text[0], &mixer_text[mixer_text_length - resid], resid);
mixer_text_length = resid;
+
+ /* update failsafe values */
+ mixer_set_failsafe();
}
break;
}
}
+
+static void
+mixer_set_failsafe()
+{
+ /*
+ * Check if a custom failsafe value has been written,
+ * else use the opportunity to set decent defaults.
+ */
+ if (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM)
+ return;
+
+ float outputs[IO_SERVO_COUNT];
+ unsigned mixed;
+
+ /* mix */
+ mixed = mixer_group.mix(&outputs[0], IO_SERVO_COUNT);
+
+ /* scale to PWM and update the servo outputs as required */
+ for (unsigned i = 0; i < mixed; i++) {
+
+ /* scale to servo output */
+ r_page_servo_failsafe[i] = (outputs[i] * 600.0f) + 1500;
+
+ }
+
+ /* disable the rest of the outputs */
+ for (unsigned i = mixed; i < IO_SERVO_COUNT; i++)
+ r_page_servo_failsafe[i] = 0;
+
+}
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index e575bd841..674f9dddd 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -85,7 +85,7 @@
#define PX4IO_P_CONFIG_ACTUATOR_COUNT 5 /* hardcoded max actuator output count */
#define PX4IO_P_CONFIG_RC_INPUT_COUNT 6 /* hardcoded max R/C input count supported */
#define PX4IO_P_CONFIG_ADC_INPUT_COUNT 7 /* hardcoded max ADC inputs */
-#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* harcoded # of relay outputs */
+#define PX4IO_P_CONFIG_RELAY_COUNT 8 /* hardcoded # of relay outputs */
/* dynamic status page */
#define PX4IO_PAGE_STATUS 1
@@ -104,6 +104,7 @@
#define PX4IO_P_STATUS_FLAGS_MIXER_OK (1 << 8) /* mixer is OK */
#define PX4IO_P_STATUS_FLAGS_ARM_SYNC (1 << 9) /* the arming state between IO and FMU is in sync */
#define PX4IO_P_STATUS_FLAGS_INIT_OK (1 << 10) /* initialisation of the IO completed without error */
+#define PX4IO_P_STATUS_FLAGS_FAILSAFE (1 << 11) /* failsafe is active */
#define PX4IO_P_STATUS_ALARMS 3 /* alarm flags - alarms latch, write 1 to a bit to clear it */
#define PX4IO_P_STATUS_ALARMS_VBATT_LOW (1 << 0) /* VBatt is very close to regulator dropout */
@@ -148,6 +149,7 @@
#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */
#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */
#define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */
+#define PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM (1 << 3) /* use custom failsafe values, not 0 values of mixer */
#define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */
#define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 9698a0f2f..df7d6dcd3 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -41,6 +41,7 @@
#include <stdbool.h>
#include <stdlib.h>
+#include <string.h>
#include <drivers/drv_hrt.h>
@@ -178,8 +179,10 @@ uint16_t r_page_rc_input_config[MAX_CONTROL_CHANNELS * PX4IO_P_RC_CONFIG_STRIDE
* PAGE 105
*
* Failsafe servo PWM values
+ *
+ * Disable pulses as default.
*/
-uint16_t r_page_servo_failsafe[IO_SERVO_COUNT];
+uint16_t r_page_servo_failsafe[IO_SERVO_COUNT] = { 0 };
void
registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num_values)
@@ -230,11 +233,14 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
case PX4IO_PAGE_FAILSAFE_PWM:
/* copy channel data */
- while ((offset < PX4IO_CONTROL_CHANNELS) && (num_values > 0)) {
+ while ((offset < IO_SERVO_COUNT) && (num_values > 0)) {
/* XXX range-check value? */
r_page_servo_failsafe[offset] = *values;
+ /* flag the failsafe values as custom */
+ r_setup_arming |= PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM;
+
offset++;
num_values--;
values++;
diff --git a/src/modules/systemlib/geo/geo.c b/src/modules/systemlib/geo/geo.c
index 6746e8ff3..6463e6489 100644
--- a/src/modules/systemlib/geo/geo.c
+++ b/src/modules/systemlib/geo/geo.c
@@ -185,12 +185,11 @@ __EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, dou
double d_lat = lat_next_rad - lat_now_rad;
double d_lon = lon_next_rad - lon_now_rad;
- double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad);
+ double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0d) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad);
double c = 2.0d * atan2(sqrt(a), sqrt(1.0d - a));
const double radius_earth = 6371000.0d;
-
- return radius_earth * c;
+ return radius_earth * c;
}
__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
diff --git a/src/modules/systemlib/geo/geo.h b/src/modules/systemlib/geo/geo.h
index 0c0b5c533..84097b49f 100644
--- a/src/modules/systemlib/geo/geo.h
+++ b/src/modules/systemlib/geo/geo.h
@@ -82,8 +82,24 @@ __EXPORT void map_projection_project(double lat, double lon, float *x, float *y)
*/
__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon);
+/**
+ * Returns the distance to the next waypoint in meters.
+ *
+ * @param lat_now current position in degrees (47.1234567°, not 471234567°)
+ * @param lon_now current position in degrees (8.1234567°, not 81234567°)
+ * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
+ * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
+ */
__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+/**
+ * Returns the bearing to the next waypoint in radians.
+ *
+ * @param lat_now current position in degrees (47.1234567°, not 471234567°)
+ * @param lon_now current position in degrees (8.1234567°, not 81234567°)
+ * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
+ * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
+ */
__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);