aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp211
-rw-r--r--src/modules/commander/commander_helper.cpp52
-rw-r--r--src/modules/commander/commander_helper.h3
-rw-r--r--src/modules/commander/gyro_calibration.cpp12
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp1049
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c109
-rw-r--r--src/modules/fw_pos_control_l1/module.mk41
-rw-r--r--src/modules/mavlink/mavlink.c2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp48
-rw-r--r--src/modules/mavlink/orb_listener.c23
-rw-r--r--src/modules/mavlink/orb_topics.h1
-rw-r--r--src/modules/mavlink/waypoints.c236
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c125
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c10
-rw-r--r--src/modules/px4iofirmware/controls.c2
-rw-r--r--src/modules/px4iofirmware/dsm.c21
-rw-r--r--src/modules/px4iofirmware/mixer.cpp2
-rw-r--r--src/modules/px4iofirmware/protocol.h2
-rw-r--r--src/modules/px4iofirmware/px4io.h2
-rw-r--r--src/modules/px4iofirmware/registers.c12
-rw-r--r--src/modules/sdlog2/sdlog2.c3
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h5
-rw-r--r--src/modules/sensors/sensor_params.c8
-rw-r--r--src/modules/sensors/sensors.cpp3
-rw-r--r--src/modules/systemlib/mixer/mixer.cpp16
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp17
-rw-r--r--src/modules/systemlib/mixer/mixer_simple.cpp44
-rw-r--r--src/modules/systemlib/param/param.c47
-rw-r--r--src/modules/systemlib/pid/pid.c28
-rw-r--r--src/modules/uORB/topics/vehicle_command.h5
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h6
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h4
32 files changed, 1732 insertions, 417 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 5eeb018fd..01b7b84d0 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -5,6 +5,7 @@
* Lorenz Meier <lm@inf.ethz.ch>
* Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -198,7 +199,7 @@ void handle_command(struct vehicle_status_s *status, struct vehicle_control_mode
*/
int commander_thread_main(int argc, char *argv[]);
-void toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed);
+void control_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed);
void check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed);
@@ -369,7 +370,13 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
transition_result_t arming_res = TRANSITION_NOT_CHANGED;
if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
- arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
+ if (safety->safety_switch_available && !safety->safety_off) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+ arming_res = TRANSITION_DENIED;
+
+ } else {
+ arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
+ }
if (arming_res == TRANSITION_CHANGED) {
mavlink_log_info(mavlink_fd, "[cmd] ARMED by command");
@@ -463,8 +470,26 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
case VEHICLE_CMD_COMPONENT_ARM_DISARM:
- // XXX implement later
- result = VEHICLE_CMD_RESULT_DENIED;
+ {
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+ if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) {
+ if (safety->safety_switch_available && !safety->safety_off) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+ arming_res = TRANSITION_DENIED;
+
+ } else {
+ arming_res = arming_state_transition(status, safety, ARMING_STATE_ARMED, armed);
+ }
+
+ if (arming_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] ARMED by component arm cmd");
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ } else {
+ mavlink_log_info(mavlink_fd, "[cmd] REJECTING component arm cmd");
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
+ }
+ }
break;
default:
@@ -561,7 +586,7 @@ int commander_thread_main(int argc, char *argv[])
/* flags for control apps */
struct vehicle_control_mode_s control_mode;
-
+
/* Initialize all flags to false */
memset(&control_mode, 0, sizeof(control_mode));
@@ -644,7 +669,6 @@ int commander_thread_main(int argc, char *argv[])
bool critical_battery_voltage_actions_done = false;
uint64_t last_idle_time = 0;
-
uint64_t start_time = 0;
bool status_changed = true;
@@ -722,7 +746,7 @@ int commander_thread_main(int argc, char *argv[])
struct subsystem_info_s info;
memset(&info, 0, sizeof(info));
- toggle_status_leds(&status, &armed, true);
+ control_status_leds(&status, &armed, true);
/* now initialized */
commander_initialized = true;
@@ -800,16 +824,6 @@ int commander_thread_main(int argc, char *argv[])
check_valid(diff_pres.timestamp, DIFFPRESS_TIMEOUT, true, &(status.condition_airspeed_valid), &status_changed);
- orb_check(cmd_sub, &updated);
-
- if (updated) {
- /* got command */
- orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
-
- /* handle it */
- handle_command(&status, &safety, &control_mode, &cmd, &armed);
- }
-
/* update safety topic */
orb_check(safety_sub, &updated);
@@ -944,11 +958,9 @@ int commander_thread_main(int argc, char *argv[])
battery_tune_played = false;
if (armed.armed) {
- // XXX not sure what should happen when voltage is low in flight
- //arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed);
} else {
- // XXX should we still allow to arm with critical battery?
- //arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed);
}
status_changed = true;
@@ -1083,10 +1095,18 @@ int commander_thread_main(int argc, char *argv[])
/* check if left stick is in lower right position and we're in MANUAL mode -> arm */
if (status.arming_state == ARMING_STATE_STANDBY &&
- status.main_state == MAIN_STATE_MANUAL &&
sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
+ if (safety.safety_switch_available && !safety.safety_off) {
+ print_reject_arm("NOT ARMING: Press safety switch first.");
+
+ } else if (status.main_state != MAIN_STATE_MANUAL) {
+ print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
+
+ } else {
+ res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
+ }
+
stick_on_counter = 0;
} else {
@@ -1106,15 +1126,8 @@ int commander_thread_main(int argc, char *argv[])
}
} else if (res == TRANSITION_DENIED) {
- /* DENIED here indicates safety switch not pressed */
-
- if (!(!safety.safety_switch_available || safety.safety_off)) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
-
- } else {
- warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
- mavlink_log_critical(mavlink_fd, "[cmd] ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
- }
+ warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
+ mavlink_log_critical(mavlink_fd, "[cmd] ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch);
}
/* fill current_status according to mode switches */
@@ -1142,6 +1155,18 @@ int commander_thread_main(int argc, char *argv[])
}
}
+
+ /* handle commands last, as the system needs to be updated to handle them */
+ orb_check(cmd_sub, &updated);
+
+ if (updated) {
+ /* got command */
+ orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
+
+ /* handle it */
+ handle_command(&status, &safety, &control_mode, &cmd, &armed);
+ }
+
/* evaluate the navigation state machine */
transition_result_t res = check_navigation_state_machine(&status, &control_mode, &local_position);
@@ -1159,9 +1184,6 @@ int commander_thread_main(int argc, char *argv[])
if (arming_state_changed || main_state_changed || navigation_state_changed) {
mavlink_log_info(mavlink_fd, "[cmd] state: arm %d, main %d, nav %d", status.arming_state, status.main_state, status.navigation_state);
status_changed = true;
-
- } else {
- status_changed = false;
}
hrt_abstime t1 = hrt_absolute_time();
@@ -1221,13 +1243,26 @@ int commander_thread_main(int argc, char *argv[])
fflush(stdout);
counter++;
- toggle_status_leds(&status, &armed, arming_state_changed || status_changed);
+ int blink_state = blink_msg_state();
+ if (blink_state > 0) {
+ /* blinking LED message, don't touch LEDs */
+ if (blink_state == 2) {
+ /* blinking LED message completed, restore normal state */
+ control_status_leds(&status, &armed, true);
+ }
+ } else {
+ /* normal state */
+ control_status_leds(&status, &armed, status_changed);
+ }
+
+ status_changed = false;
usleep(COMMANDER_MONITORING_INTERVAL);
}
/* wait for threads to complete */
ret = pthread_join(commander_low_prio_thread, NULL);
+
if (ret) {
warn("join failed", ret);
}
@@ -1268,8 +1303,48 @@ check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *val
}
void
-toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed)
+control_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed)
{
+ /* driving rgbled */
+ if (changed) {
+ bool set_normal_color = false;
+ /* set mode */
+ if (status->arming_state == ARMING_STATE_ARMED) {
+ rgbled_set_mode(RGBLED_MODE_ON);
+ set_normal_color = true;
+
+ } else if (status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+ rgbled_set_color(RGBLED_COLOR_RED);
+
+ } else if (status->arming_state == ARMING_STATE_STANDBY) {
+ rgbled_set_mode(RGBLED_MODE_BREATHE);
+ set_normal_color = true;
+
+ } else { // STANDBY_ERROR and other states
+ rgbled_set_mode(RGBLED_MODE_BLINK_NORMAL);
+ rgbled_set_color(RGBLED_COLOR_RED);
+ }
+
+ if (set_normal_color) {
+ /* set color */
+ if (status->battery_warning != VEHICLE_BATTERY_WARNING_NONE) {
+ if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW) {
+ rgbled_set_color(RGBLED_COLOR_AMBER);
+ }
+ /* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */
+
+ } else {
+ if (status->condition_local_position_valid) {
+ rgbled_set_color(RGBLED_COLOR_GREEN);
+
+ } else {
+ rgbled_set_color(RGBLED_COLOR_BLUE);
+ }
+ }
+ }
+ }
+
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* this runs at around 20Hz, full cycle is 16 ticks = 10/16Hz */
@@ -1290,46 +1365,6 @@ toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool chang
#endif
- if (changed) {
- /* XXX TODO blink fast when armed and serious error occurs */
-
- if (armed->armed) {
- rgbled_set_mode(RGBLED_MODE_ON);
- } else if (armed->ready_to_arm) {
- rgbled_set_mode(RGBLED_MODE_BREATHE);
- } else {
- rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
- }
- }
-
- if (status->battery_warning != VEHICLE_BATTERY_WARNING_NONE) {
- switch (status->battery_warning) {
- case VEHICLE_BATTERY_WARNING_LOW:
- rgbled_set_color(RGBLED_COLOR_YELLOW);
- break;
- case VEHICLE_BATTERY_WARNING_CRITICAL:
- rgbled_set_color(RGBLED_COLOR_AMBER);
- break;
- default:
- break;
- }
- } else {
- switch (status->main_state) {
- case MAIN_STATE_MANUAL:
- rgbled_set_color(RGBLED_COLOR_WHITE);
- break;
- case MAIN_STATE_SEATBELT:
- case MAIN_STATE_EASY:
- rgbled_set_color(RGBLED_COLOR_GREEN);
- break;
- case MAIN_STATE_AUTO:
- rgbled_set_color(RGBLED_COLOR_BLUE);
- break;
- default:
- break;
- }
- }
-
/* give system warnings on error LED, XXX maybe add memory usage warning too */
if (status->load > 0.95f) {
if (leds_counter % 2 == 0)
@@ -1497,16 +1532,18 @@ check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_c
return TRANSITION_NOT_CHANGED;
}
}
+
if (status->navigation_state != NAVIGATION_STATE_AUTO_TAKEOFF &&
- status->navigation_state != NAVIGATION_STATE_AUTO_LOITER &&
- status->navigation_state != NAVIGATION_STATE_AUTO_MISSION &&
- status->navigation_state != NAVIGATION_STATE_AUTO_RTL) {
+ status->navigation_state != NAVIGATION_STATE_AUTO_LOITER &&
+ status->navigation_state != NAVIGATION_STATE_AUTO_MISSION &&
+ status->navigation_state != NAVIGATION_STATE_AUTO_RTL) {
/* possibly on ground, switch to TAKEOFF if needed */
if (local_pos->z > -takeoff_alt || status->condition_landed) {
res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
return res;
}
}
+
/* switch to AUTO mode */
if (status->rc_signal_found_once && !status->rc_signal_lost) {
/* act depending on switches when manual control enabled */
@@ -1524,18 +1561,20 @@ check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_c
res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_LOITER, control_mode);
}
}
+
} else {
/* switch to MISSION when no RC control and first time in some AUTO mode */
if (status->navigation_state == NAVIGATION_STATE_AUTO_LOITER ||
- status->navigation_state == NAVIGATION_STATE_AUTO_MISSION ||
- status->navigation_state == NAVIGATION_STATE_AUTO_RTL ||
- status->navigation_state == NAVIGATION_STATE_AUTO_LAND) {
+ status->navigation_state == NAVIGATION_STATE_AUTO_MISSION ||
+ status->navigation_state == NAVIGATION_STATE_AUTO_RTL ||
+ status->navigation_state == NAVIGATION_STATE_AUTO_LAND) {
res = TRANSITION_NOT_CHANGED;
} else {
res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_MISSION, control_mode);
}
}
+
} else {
/* disarmed, always switch to AUTO_READY */
res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_READY, control_mode);
@@ -1762,35 +1801,41 @@ void *commander_low_prio_loop(void *arg)
if (((int)(cmd.param1)) == 0) {
int ret = param_load_default();
+
if (ret == OK) {
mavlink_log_info(mavlink_fd, "[cmd] parameters loaded");
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
} else {
mavlink_log_critical(mavlink_fd, "[cmd] parameters load ERROR");
+
/* convenience as many parts of NuttX use negative errno */
if (ret < 0)
ret = -ret;
if (ret < 1000)
mavlink_log_critical(mavlink_fd, "[cmd] %s", strerror(ret));
+
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
} else if (((int)(cmd.param1)) == 1) {
int ret = param_save_default();
+
if (ret == OK) {
mavlink_log_info(mavlink_fd, "[cmd] parameters saved");
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
} else {
mavlink_log_critical(mavlink_fd, "[cmd] parameters save error");
+
/* convenience as many parts of NuttX use negative errno */
if (ret < 0)
ret = -ret;
if (ret < 1000)
mavlink_log_critical(mavlink_fd, "[cmd] %s", strerror(ret));
+
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
}
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index 7feace2b4..565b4b66a 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -3,6 +3,7 @@
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
* Author: Thomas Gubler <thomasgubler@student.ethz.ch>
* Julian Oes <joes@student.ethz.ch>
+ * Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -55,7 +56,6 @@
#include <drivers/drv_led.h>
#include <drivers/drv_rgbled.h>
-
#include "commander_helper.h"
/* oddly, ERROR is not defined for c++ */
@@ -64,25 +64,28 @@
#endif
static const int ERROR = -1;
+#define BLINK_MSG_TIME 700000 // 3 fast blinks
+
bool is_multirotor(const struct vehicle_status_s *current_status)
{
return ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_OCTOROTOR) ||
- (current_status->system_type == VEHICLE_TYPE_TRICOPTER));
+ (current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_OCTOROTOR) ||
+ (current_status->system_type == VEHICLE_TYPE_TRICOPTER));
}
bool is_rotary_wing(const struct vehicle_status_s *current_status)
{
return is_multirotor(current_status) || (current_status->system_type == VEHICLE_TYPE_HELICOPTER)
- || (current_status->system_type == VEHICLE_TYPE_COAXIAL);
+ || (current_status->system_type == VEHICLE_TYPE_COAXIAL);
}
static int buzzer;
+static hrt_abstime blink_msg_end;
int buzzer_init()
{
- buzzer = open("/dev/tone_alarm", O_WRONLY);
+ buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY);
if (buzzer < 0) {
warnx("Buzzer: open fail\n");
@@ -104,16 +107,25 @@ void tune_error()
void tune_positive()
{
+ blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
+ rgbled_set_color(RGBLED_COLOR_GREEN);
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_POSITIVE_TUNE);
}
void tune_neutral()
{
+ blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
+ rgbled_set_color(RGBLED_COLOR_WHITE);
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEUTRAL_TUNE);
}
void tune_negative()
{
+ blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
+ rgbled_set_color(RGBLED_COLOR_RED);
+ rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
}
@@ -132,18 +144,31 @@ int tune_critical_bat()
return ioctl(buzzer, TONE_SET_ALARM, TONE_BATTERY_WARNING_FAST_TUNE);
}
-
-
void tune_stop()
{
ioctl(buzzer, TONE_SET_ALARM, TONE_STOP_TUNE);
}
+int blink_msg_state()
+{
+ if (blink_msg_end == 0) {
+ return 0;
+
+ } else if (hrt_absolute_time() > blink_msg_end) {
+ return 2;
+
+ } else {
+ return 1;
+ }
+}
+
static int leds;
static int rgbleds;
int led_init()
{
+ blink_msg_end = 0;
+
/* first open normal LEDs */
leds = open(LED_DEVICE_PATH, 0);
@@ -159,6 +184,7 @@ int led_init()
warnx("Blue LED: ioctl fail\n");
return ERROR;
}
+
#endif
if (ioctl(leds, LED_ON, LED_AMBER)) {
@@ -168,6 +194,7 @@ int led_init()
/* then try RGB LEDs, this can fail on FMUv1*/
rgbleds = open(RGBLED_DEVICE_PATH, 0);
+
if (rgbleds == -1) {
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
errx(1, "Unable to open " RGBLED_DEVICE_PATH);
@@ -203,19 +230,22 @@ int led_off(int led)
return ioctl(leds, LED_OFF, led);
}
-void rgbled_set_color(rgbled_color_t color) {
+void rgbled_set_color(rgbled_color_t color)
+{
if (rgbleds != -1)
ioctl(rgbleds, RGBLED_SET_COLOR, (unsigned long)color);
}
-void rgbled_set_mode(rgbled_mode_t mode) {
+void rgbled_set_mode(rgbled_mode_t mode)
+{
if (rgbleds != -1)
ioctl(rgbleds, RGBLED_SET_MODE, (unsigned long)mode);
}
-void rgbled_set_pattern(rgbled_pattern_t *pattern) {
+void rgbled_set_pattern(rgbled_pattern_t *pattern)
+{
if (rgbleds != -1)
ioctl(rgbleds, RGBLED_SET_PATTERN, (unsigned long)pattern);
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
index 027d0535f..e9514446c 100644
--- a/src/modules/commander/commander_helper.h
+++ b/src/modules/commander/commander_helper.h
@@ -62,6 +62,7 @@ int tune_arm(void);
int tune_low_bat(void);
int tune_critical_bat(void);
void tune_stop(void);
+int blink_msg_state();
int led_init(void);
void led_deinit(void);
@@ -70,9 +71,7 @@ int led_on(int led);
int led_off(int led);
void rgbled_set_color(rgbled_color_t color);
-
void rgbled_set_mode(rgbled_mode_t mode);
-
void rgbled_set_pattern(rgbled_pattern_t *pattern);
/**
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 82a0349c9..369e6da62 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -163,7 +163,9 @@ int do_gyro_calibration(int mavlink_fd)
return ERROR;
}
+ mavlink_log_info(mavlink_fd, "offset calibration done.");
+#if 0
/*** --- SCALING --- ***/
mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip.");
@@ -241,9 +243,14 @@ int do_gyro_calibration(int mavlink_fd)
}
float gyro_scale = baseline_integral / gyro_integral;
- float gyro_scales[] = { gyro_scale, gyro_scale, gyro_scale };
+
warnx("gyro scale: yaw (z): %6.4f", (double)gyro_scale);
mavlink_log_info(mavlink_fd, "gyro scale: yaw (z): %6.4f", (double)gyro_scale);
+#else
+ float gyro_scales[] = { 1.0f, 1.0f, 1.0f };
+#endif
+
+
if (isfinite(gyro_scales[0]) && isfinite(gyro_scales[1]) && isfinite(gyro_scales[2])) {
@@ -277,9 +284,6 @@ int do_gyro_calibration(int mavlink_fd)
warn("WARNING: auto-save of params to storage failed");
}
- // char buf[50];
- // sprintf(buf, "cal: x:%8.4f y:%8.4f z:%8.4f", (double)gyro_offset[0], (double)gyro_offset[1], (double)gyro_offset[2]);
- // mavlink_log_info(mavlink_fd, buf);
mavlink_log_info(mavlink_fd, "gyro calibration done");
/* third beep by cal end routine */
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
new file mode 100644
index 000000000..3d5bce134
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -0,0 +1,1049 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+
+/**
+ * @file fw_pos_control_l1_main.c
+ * Implementation of a generic position controller based on the L1 norm. Outputs a bank / roll
+ * angle, equivalent to a lateral motion (for copters and rovers).
+ *
+ * Original publication for horizontal control class:
+ * S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
+ * Proceedings of the AIAA Guidance, Navigation and Control
+ * Conference, Aug 2004. AIAA-2004-4900.
+ *
+ * Original implementation for total energy control class:
+ * Paul Riseborough and Andrew Tridgell, 2013 (code in lib/external_lgpl)
+ *
+ * More details and acknowledgements in the referenced library headers.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <math.h>
+#include <poll.h>
+#include <time.h>
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_accel.h>
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <systemlib/pid/pid.h>
+#include <geo/geo.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+#include <mathlib/mathlib.h>
+
+#include <ecl/l1/ecl_l1_pos_controller.h>
+#include <external_lgpl/tecs/tecs.h>
+
+/**
+ * L1 control app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]);
+
+class FixedwingPositionControl
+{
+public:
+ /**
+ * Constructor
+ */
+ FixedwingPositionControl();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~FixedwingPositionControl();
+
+ /**
+ * Start the sensors task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+private:
+
+ bool _task_should_exit; /**< if true, sensor task should exit */
+ int _control_task; /**< task handle for sensor task */
+
+ int _global_pos_sub;
+ int _global_set_triplet_sub;
+ int _att_sub; /**< vehicle attitude subscription */
+ int _attitude_sub; /**< raw rc channels data subscription */
+ int _airspeed_sub; /**< airspeed subscription */
+ int _control_mode_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_control_sub; /**< notification of manual control updates */
+ int _accel_sub; /**< body frame accelerations */
+
+ orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
+
+ struct vehicle_attitude_s _att; /**< vehicle attitude */
+ struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
+ struct manual_control_setpoint_s _manual; /**< r/c channel data */
+ struct airspeed_s _airspeed; /**< airspeed */
+ struct vehicle_control_mode_s _control_mode; /**< vehicle status */
+ struct vehicle_global_position_s _global_pos; /**< global vehicle position */
+ struct vehicle_global_position_set_triplet_s _global_triplet; /**< triplet of global setpoints */
+ struct accel_report _accel; /**< body frame accelerations */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+
+ bool _setpoint_valid; /**< flag if the position control setpoint is valid */
+
+ /** manual control states */
+ float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
+ float _loiter_hold_lat;
+ float _loiter_hold_lon;
+ float _loiter_hold_alt;
+ bool _loiter_hold;
+
+ float _launch_lat;
+ float _launch_lon;
+ float _launch_alt;
+ bool _launch_valid;
+
+ /* throttle and airspeed states */
+ float _airspeed_error; ///< airspeed error to setpoint in m/s
+ bool _airspeed_valid; ///< flag if a valid airspeed estimate exists
+ uint64_t _airspeed_last_valid; ///< last time airspeed was valid. Used to detect sensor failures
+ float _groundspeed_undershoot; ///< ground speed error to min. speed in m/s
+ bool _global_pos_valid; ///< global position is valid
+ math::Dcm _R_nb; ///< current attitude
+
+ ECL_L1_Pos_Controller _l1_control;
+ TECS _tecs;
+
+ struct {
+ float l1_period;
+ float l1_damping;
+
+ float time_const;
+ float min_sink_rate;
+ float max_sink_rate;
+ float max_climb_rate;
+ float throttle_damp;
+ float integrator_gain;
+ float vertical_accel_limit;
+ float height_comp_filter_omega;
+ float speed_comp_filter_omega;
+ float roll_throttle_compensation;
+ float speed_weight;
+ float pitch_damping;
+
+ float airspeed_min;
+ float airspeed_trim;
+ float airspeed_max;
+
+ float pitch_limit_min;
+ float pitch_limit_max;
+ float throttle_min;
+ float throttle_max;
+ float throttle_cruise;
+
+ float loiter_hold_radius;
+ } _parameters; /**< local copies of interesting parameters */
+
+ struct {
+
+ param_t l1_period;
+ param_t l1_damping;
+
+ param_t time_const;
+ param_t min_sink_rate;
+ param_t max_sink_rate;
+ param_t max_climb_rate;
+ param_t throttle_damp;
+ param_t integrator_gain;
+ param_t vertical_accel_limit;
+ param_t height_comp_filter_omega;
+ param_t speed_comp_filter_omega;
+ param_t roll_throttle_compensation;
+ param_t speed_weight;
+ param_t pitch_damping;
+
+ param_t airspeed_min;
+ param_t airspeed_trim;
+ param_t airspeed_max;
+
+ param_t pitch_limit_min;
+ param_t pitch_limit_max;
+ param_t throttle_min;
+ param_t throttle_max;
+ param_t throttle_cruise;
+
+ param_t loiter_hold_radius;
+ } _parameter_handles; /**< handles for interesting parameters */
+
+
+ /**
+ * Update our local parameter cache.
+ */
+ int parameters_update();
+
+ /**
+ * Update control outputs
+ *
+ */
+ void control_update();
+
+ /**
+ * Check for changes in vehicle status.
+ */
+ void vehicle_control_mode_poll();
+
+ /**
+ * Check for airspeed updates.
+ */
+ bool vehicle_airspeed_poll();
+
+ /**
+ * Check for position updates.
+ */
+ void vehicle_attitude_poll();
+
+ /**
+ * Check for accel updates.
+ */
+ void vehicle_accel_poll();
+
+ /**
+ * Check for set triplet updates.
+ */
+ void vehicle_setpoint_poll();
+
+ /**
+ * Control position.
+ */
+ bool control_position(const math::Vector2f &global_pos, const math::Vector2f &ground_speed,
+ const struct vehicle_global_position_set_triplet_s &global_triplet);
+
+ float calculate_target_airspeed(float airspeed_demand);
+ void calculate_gndspeed_undershoot();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+
+ /**
+ * Main sensor collection task.
+ */
+ void task_main() __attribute__((noreturn));
+};
+
+namespace l1_control
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+FixedwingPositionControl *g_control;
+}
+
+FixedwingPositionControl::FixedwingPositionControl() :
+
+ _task_should_exit(false),
+ _control_task(-1),
+
+/* subscriptions */
+ _global_pos_sub(-1),
+ _global_set_triplet_sub(-1),
+ _att_sub(-1),
+ _airspeed_sub(-1),
+ _control_mode_sub(-1),
+ _params_sub(-1),
+ _manual_control_sub(-1),
+
+/* publications */
+ _attitude_sp_pub(-1),
+
+/* performance counters */
+ _loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
+/* states */
+ _setpoint_valid(false),
+ _loiter_hold(false),
+ _airspeed_error(0.0f),
+ _airspeed_valid(false),
+ _groundspeed_undershoot(0.0f),
+ _global_pos_valid(false)
+{
+ _parameter_handles.l1_period = param_find("FW_L1_PERIOD");
+ _parameter_handles.l1_damping = param_find("FW_L1_DAMPING");
+ _parameter_handles.loiter_hold_radius = param_find("FW_LOITER_R");
+
+ _parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
+ _parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
+ _parameter_handles.airspeed_max = param_find("FW_AIRSPD_MAX");
+
+ _parameter_handles.pitch_limit_min = param_find("FW_P_LIM_MIN");
+ _parameter_handles.pitch_limit_max = param_find("FW_P_LIM_MAX");
+ _parameter_handles.throttle_min = param_find("FW_THR_MIN");
+ _parameter_handles.throttle_max = param_find("FW_THR_MAX");
+ _parameter_handles.throttle_cruise = param_find("FW_THR_CRUISE");
+
+ _parameter_handles.time_const = param_find("FW_T_TIME_CONST");
+ _parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
+ _parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX");
+ _parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX");
+ _parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP");
+ _parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN");
+ _parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC");
+ _parameter_handles.height_comp_filter_omega = param_find("FW_T_HGT_OMEGA");
+ _parameter_handles.speed_comp_filter_omega = param_find("FW_T_SPD_OMEGA");
+ _parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR");
+ _parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
+ _parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
+
+ /* fetch initial parameter values */
+ parameters_update();
+}
+
+FixedwingPositionControl::~FixedwingPositionControl()
+{
+ if (_control_task != -1) {
+
+ /* task wakes up every 100ms or so at the longest */
+ _task_should_exit = true;
+
+ /* wait for a second for the task to quit at our request */
+ unsigned i = 0;
+
+ do {
+ /* wait 20ms */
+ usleep(20000);
+
+ /* if we have given up, kill it */
+ if (++i > 50) {
+ task_delete(_control_task);
+ break;
+ }
+ } while (_control_task != -1);
+ }
+
+ l1_control::g_control = nullptr;
+}
+
+int
+FixedwingPositionControl::parameters_update()
+{
+
+ /* L1 control parameters */
+ param_get(_parameter_handles.l1_damping, &(_parameters.l1_damping));
+ param_get(_parameter_handles.l1_period, &(_parameters.l1_period));
+ param_get(_parameter_handles.loiter_hold_radius, &(_parameters.loiter_hold_radius));
+
+ param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
+ param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
+ param_get(_parameter_handles.airspeed_max, &(_parameters.airspeed_max));
+
+ param_get(_parameter_handles.pitch_limit_min, &(_parameters.pitch_limit_min));
+ param_get(_parameter_handles.pitch_limit_max, &(_parameters.pitch_limit_max));
+ param_get(_parameter_handles.throttle_min, &(_parameters.throttle_min));
+ param_get(_parameter_handles.throttle_max, &(_parameters.throttle_max));
+ param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise));
+
+ param_get(_parameter_handles.time_const, &(_parameters.time_const));
+ param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate));
+ param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate));
+ param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp));
+ param_get(_parameter_handles.integrator_gain, &(_parameters.integrator_gain));
+ param_get(_parameter_handles.vertical_accel_limit, &(_parameters.vertical_accel_limit));
+ param_get(_parameter_handles.height_comp_filter_omega, &(_parameters.height_comp_filter_omega));
+ param_get(_parameter_handles.speed_comp_filter_omega, &(_parameters.speed_comp_filter_omega));
+ param_get(_parameter_handles.roll_throttle_compensation, &(_parameters.roll_throttle_compensation));
+ param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight));
+ param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping));
+ param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate));
+
+ _l1_control.set_l1_damping(_parameters.l1_damping);
+ _l1_control.set_l1_period(_parameters.l1_period);
+
+ _tecs.set_time_const(_parameters.time_const);
+ _tecs.set_min_sink_rate(_parameters.min_sink_rate);
+ _tecs.set_max_sink_rate(_parameters.max_sink_rate);
+ _tecs.set_throttle_damp(_parameters.throttle_damp);
+ _tecs.set_integrator_gain(_parameters.integrator_gain);
+ _tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit);
+ _tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega);
+ _tecs.set_speed_comp_filter_omega(_parameters.speed_comp_filter_omega);
+ _tecs.set_roll_throttle_compensation(math::radians(_parameters.roll_throttle_compensation));
+ _tecs.set_speed_weight(_parameters.speed_weight);
+ _tecs.set_pitch_damping(_parameters.pitch_damping);
+ _tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
+ _tecs.set_indicated_airspeed_max(_parameters.airspeed_min);
+ _tecs.set_max_climb_rate(_parameters.max_climb_rate);
+
+ /* sanity check parameters */
+ if (_parameters.airspeed_max < _parameters.airspeed_min ||
+ _parameters.airspeed_max < 5.0f ||
+ _parameters.airspeed_min > 100.0f ||
+ _parameters.airspeed_trim < _parameters.airspeed_min ||
+ _parameters.airspeed_trim > _parameters.airspeed_max) {
+ warnx("error: airspeed parameters invalid");
+ return 1;
+ }
+
+ return OK;
+}
+
+void
+FixedwingPositionControl::vehicle_control_mode_poll()
+{
+ bool vstatus_updated;
+
+ /* Check HIL state if vehicle status has changed */
+ orb_check(_control_mode_sub, &vstatus_updated);
+
+ if (vstatus_updated) {
+
+ bool was_armed = _control_mode.flag_armed;
+
+ orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode);
+
+ if (!was_armed && _control_mode.flag_armed) {
+ _launch_lat = _global_pos.lat / 1e7f;
+ _launch_lon = _global_pos.lon / 1e7f;
+ _launch_alt = _global_pos.alt;
+ _launch_valid = true;
+ }
+ }
+}
+
+bool
+FixedwingPositionControl::vehicle_airspeed_poll()
+{
+ /* check if there is an airspeed update or if it timed out */
+ bool airspeed_updated;
+ orb_check(_airspeed_sub, &airspeed_updated);
+
+ if (airspeed_updated) {
+ orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
+ _airspeed_valid = true;
+ _airspeed_last_valid = hrt_absolute_time();
+ return true;
+
+ } else {
+
+ /* no airspeed updates for one second */
+ if (_airspeed_valid && (hrt_absolute_time() - _airspeed_last_valid) > 1e6) {
+ _airspeed_valid = false;
+ }
+ }
+
+ /* update TECS state */
+ _tecs.enable_airspeed(_airspeed_valid);
+
+ return false;
+}
+
+void
+FixedwingPositionControl::vehicle_attitude_poll()
+{
+ /* check if there is a new position */
+ bool att_updated;
+ orb_check(_att_sub, &att_updated);
+
+ if (att_updated) {
+ orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
+
+ /* set rotation matrix */
+ for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
+ _R_nb(i, j) = _att.R[i][j];
+ }
+}
+
+void
+FixedwingPositionControl::vehicle_accel_poll()
+{
+ /* check if there is a new position */
+ bool accel_updated;
+ orb_check(_accel_sub, &accel_updated);
+
+ if (accel_updated) {
+ orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
+ }
+}
+
+void
+FixedwingPositionControl::vehicle_setpoint_poll()
+{
+ /* check if there is a new setpoint */
+ bool global_sp_updated;
+ orb_check(_global_set_triplet_sub, &global_sp_updated);
+
+ if (global_sp_updated) {
+ orb_copy(ORB_ID(vehicle_global_position_set_triplet), _global_set_triplet_sub, &_global_triplet);
+ _setpoint_valid = true;
+ }
+}
+
+void
+FixedwingPositionControl::task_main_trampoline(int argc, char *argv[])
+{
+ l1_control::g_control->task_main();
+}
+
+float
+FixedwingPositionControl::calculate_target_airspeed(float airspeed_demand)
+{
+ float airspeed;
+
+ if (_airspeed_valid) {
+ airspeed = _airspeed.true_airspeed_m_s;
+
+ } else {
+ airspeed = _parameters.airspeed_min + (_parameters.airspeed_max - _parameters.airspeed_min) / 2.0f;
+ }
+
+ /* cruise airspeed for all modes unless modified below */
+ float target_airspeed = airspeed_demand;
+
+ /* add minimum ground speed undershoot (only non-zero in presence of sufficient wind) */
+ target_airspeed += _groundspeed_undershoot;
+
+ if (0/* throttle nudging enabled */) {
+ //target_airspeed += nudge term.
+ }
+
+ /* sanity check: limit to range */
+ target_airspeed = math::constrain(target_airspeed, _parameters.airspeed_min, _parameters.airspeed_max);
+
+ /* plain airspeed error */
+ _airspeed_error = target_airspeed - airspeed;
+
+ return target_airspeed;
+}
+
+void
+FixedwingPositionControl::calculate_gndspeed_undershoot()
+{
+
+ if (_global_pos_valid) {
+ /* get ground speed vector */
+ math::Vector2f ground_speed_vector(_global_pos.vx, _global_pos.vy);
+
+ /* rotate with current attitude */
+ math::Vector2f yaw_vector(_R_nb(0, 0), _R_nb(1, 0));
+ yaw_vector.normalize();
+ float ground_speed_body = yaw_vector * ground_speed_vector;
+
+ /*
+ * Ground speed undershoot is the amount of ground velocity not reached
+ * by the plane. Consequently it is zero if airspeed is >= min ground speed
+ * and positive if airspeed < min ground speed.
+ *
+ * This error value ensures that a plane (as long as its throttle capability is
+ * not exceeded) travels towards a waypoint (and is not pushed more and more away
+ * by wind). Not countering this would lead to a fly-away.
+ */
+ _groundspeed_undershoot = math::max(_parameters.airspeed_min - ground_speed_body, 0.0f);
+
+ } else {
+ _groundspeed_undershoot = 0;
+ }
+}
+
+bool
+FixedwingPositionControl::control_position(const math::Vector2f &current_position, const math::Vector2f &ground_speed,
+ const struct vehicle_global_position_set_triplet_s &global_triplet)
+{
+ bool setpoint = true;
+
+ calculate_gndspeed_undershoot();
+
+ float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
+
+ // XXX re-visit
+ float baro_altitude = _global_pos.alt;
+
+ /* filter speed and altitude for controller */
+ math::Vector3 accel_body(_accel.x, _accel.y, _accel.z);
+ math::Vector3 accel_earth = _R_nb.transpose() * accel_body;
+
+ _tecs.update_50hz(baro_altitude, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
+ float altitude_error = _global_triplet.current.altitude - _global_pos.alt;
+
+ /* AUTONOMOUS FLIGHT */
+
+ // XXX this should only execute if auto AND safety off (actuators active),
+ // else integrators should be constantly reset.
+ if (_control_mode.flag_control_position_enabled) {
+
+ /* execute navigation once we have a setpoint */
+ if (_setpoint_valid) {
+
+ float altitude_error = _global_triplet.current.altitude - _global_pos.alt;
+
+ /* current waypoint (the one currently heading for) */
+ math::Vector2f next_wp(global_triplet.current.lat / 1e7f, global_triplet.current.lon / 1e7f);
+
+ /* previous waypoint */
+ math::Vector2f prev_wp;
+
+ if (global_triplet.previous_valid) {
+ prev_wp.setX(global_triplet.previous.lat / 1e7f);
+ prev_wp.setY(global_triplet.previous.lon / 1e7f);
+
+ } else {
+ /*
+ * No valid next waypoint, go for heading hold.
+ * This is automatically handled by the L1 library.
+ */
+ prev_wp.setX(global_triplet.current.lat / 1e7f);
+ prev_wp.setY(global_triplet.current.lon / 1e7f);
+
+ }
+
+ // XXX add RTL switch
+ if (global_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH && _launch_valid) {
+
+ math::Vector2f rtl_pos(_launch_lat, _launch_lon);
+
+ _l1_control.navigate_waypoints(rtl_pos, rtl_pos, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _launch_alt, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ // XXX handle case when having arrived at home (loiter)
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_WAYPOINT) {
+ /* waypoint is a plain navigation waypoint */
+ _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ global_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ global_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
+
+ /* waypoint is a loiter waypoint */
+ _l1_control.navigate_loiter(next_wp, current_position, global_triplet.current.loiter_radius,
+ global_triplet.current.loiter_direction, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_LAND) {
+
+ _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ /* apply minimum pitch (flare) and limit roll if close to touch down, altitude error is negative (going down) */
+ // XXX this could make a great param
+ if (altitude_error > -20.0f) {
+
+ float flare_angle_rad = math::radians(15.0f);//math::radians(global_triplet.current.param1)
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_min),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ true, flare_angle_rad,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ /* limit roll motion to prevent wings from touching the ground first */
+ _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-20.0f), math::radians(20.0f));
+
+ } else {
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ }
+
+ } else if (global_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) {
+
+ _l1_control.navigate_waypoints(prev_wp, next_wp, current_position, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ /* apply minimum pitch and limit roll if target altitude is not within 10 meters */
+ if (altitude_error > 10.0f) {
+
+ /* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_min),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ true, math::max(math::radians(global_triplet.current.param1), math::radians(10.0f)),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ /* limit roll motion to ensure enough lift */
+ _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
+
+ } else {
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_triplet.current.altitude, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, math::radians(_parameters.pitch_limit_min),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ }
+ }
+
+ // warnx("nav bearing: %8.4f bearing err: %8.4f target bearing: %8.4f", (double)_l1_control.nav_bearing(),
+ // (double)_l1_control.bearing_error(), (double)_l1_control.target_bearing());
+ // warnx("prev wp: %8.4f/%8.4f, next wp: %8.4f/%8.4f prev:%s", (double)prev_wp.getX(), (double)prev_wp.getY(),
+ // (double)next_wp.getX(), (double)next_wp.getY(), (global_triplet.previous_valid) ? "valid" : "invalid");
+
+ // XXX at this point we always want no loiter hold if a
+ // mission is active
+ _loiter_hold = false;
+
+ } else if (_control_mode.flag_armed) {
+
+ /* hold position, but only if armed, climb 20m in case this is engaged on ground level */
+
+ // XXX rework with smarter state machine
+
+ if (!_loiter_hold) {
+ _loiter_hold_lat = _global_pos.lat / 1e7f;
+ _loiter_hold_lon = _global_pos.lon / 1e7f;
+ _loiter_hold_alt = _global_pos.alt + 25.0f;
+ _loiter_hold = true;
+ }
+
+ float altitude_error = _loiter_hold_alt - _global_pos.alt;
+
+ math::Vector2f loiter_hold_pos(_loiter_hold_lat, _loiter_hold_lon);
+
+ /* loiter around current position */
+ _l1_control.navigate_loiter(loiter_hold_pos, current_position, _parameters.loiter_hold_radius,
+ 1, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+
+ /* climb with full throttle if the altitude error is bigger than 5 meters */
+ bool climb_out = (altitude_error > 5);
+
+ float min_pitch;
+
+ if (climb_out) {
+ min_pitch = math::radians(20.0f);
+
+ } else {
+ min_pitch = math::radians(_parameters.pitch_limit_min);
+ }
+
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _loiter_hold_alt, calculate_target_airspeed(_parameters.airspeed_trim),
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ climb_out, min_pitch,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+
+ if (climb_out) {
+ /* limit roll motion to ensure enough lift */
+ _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
+ }
+ }
+
+ } else if (0/* seatbelt mode enabled */) {
+
+ /** SEATBELT FLIGHT **/
+
+ if (0/* switched from another mode to seatbelt */) {
+ _seatbelt_hold_heading = _att.yaw;
+ }
+
+ if (0/* seatbelt on and manual control yaw non-zero */) {
+ _seatbelt_hold_heading = _att.yaw + _manual.yaw;
+ }
+
+ /* if in seatbelt mode, set airspeed based on manual control */
+
+ // XXX check if ground speed undershoot should be applied here
+ float seatbelt_airspeed = _parameters.airspeed_min +
+ (_parameters.airspeed_max - _parameters.airspeed_min) *
+ _manual.throttle;
+
+ _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
+ _att_sp.roll_body = _l1_control.nav_roll();
+ _att_sp.yaw_body = _l1_control.nav_bearing();
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
+ seatbelt_airspeed,
+ _airspeed.indicated_airspeed_m_s, eas2tas,
+ false, _parameters.pitch_limit_min,
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ _parameters.pitch_limit_min, _parameters.pitch_limit_max);
+
+ } else {
+
+ /** MANUAL FLIGHT **/
+
+ /* no flight mode applies, do not publish an attitude setpoint */
+ setpoint = false;
+ }
+
+ _att_sp.pitch_body = _tecs.get_pitch_demand();
+ _att_sp.thrust = _tecs.get_throttle_demand();
+
+ return setpoint;
+}
+
+void
+FixedwingPositionControl::task_main()
+{
+
+ /* inform about start */
+ warnx("Initializing..");
+ fflush(stdout);
+
+ /*
+ * do subscriptions
+ */
+ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
+ _global_set_triplet_sub = orb_subscribe(ORB_ID(vehicle_global_position_set_triplet));
+ _att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ _accel_sub = orb_subscribe(ORB_ID(sensor_accel));
+ _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _params_sub = orb_subscribe(ORB_ID(parameter_update));
+ _manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+
+ /* rate limit vehicle status updates to 5Hz */
+ orb_set_interval(_control_mode_sub, 200);
+ /* rate limit position updates to 50 Hz */
+ orb_set_interval(_global_pos_sub, 20);
+
+ /* abort on a nonzero return value from the parameter init */
+ if (parameters_update()) {
+ /* parameter setup went wrong, abort */
+ warnx("aborting startup due to errors.");
+ _task_should_exit = true;
+ }
+
+ /* wakeup source(s) */
+ struct pollfd fds[2];
+
+ /* Setup of loop */
+ fds[0].fd = _params_sub;
+ fds[0].events = POLLIN;
+ fds[1].fd = _global_pos_sub;
+ fds[1].events = POLLIN;
+
+ while (!_task_should_exit) {
+
+ /* wait for up to 500ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
+
+ /* timed out - periodic check for _task_should_exit, etc. */
+ if (pret == 0)
+ continue;
+
+ /* this is undesirable but not much we can do - might want to flag unhappy status */
+ if (pret < 0) {
+ warn("poll error %d, %d", pret, errno);
+ continue;
+ }
+
+ perf_begin(_loop_perf);
+
+ /* check vehicle status for changes to publication state */
+ vehicle_control_mode_poll();
+
+ /* only update parameters if they changed */
+ if (fds[0].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+
+ /* update parameters from storage */
+ parameters_update();
+ }
+
+ /* only run controller if position changed */
+ if (fds[1].revents & POLLIN) {
+
+
+ static uint64_t last_run = 0;
+ float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
+ last_run = hrt_absolute_time();
+
+ /* guard against too large deltaT's */
+ if (deltaT > 1.0f)
+ deltaT = 0.01f;
+
+ /* load local copies */
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+
+ // XXX add timestamp check
+ _global_pos_valid = true;
+
+ vehicle_attitude_poll();
+ vehicle_setpoint_poll();
+ vehicle_accel_poll();
+ vehicle_airspeed_poll();
+ // vehicle_baro_poll();
+
+ math::Vector2f ground_speed(_global_pos.vx, _global_pos.vy);
+ math::Vector2f current_position(_global_pos.lat / 1e7f, _global_pos.lon / 1e7f);
+
+ /*
+ * Attempt to control position, on success (= sensors present and not in manual mode),
+ * publish setpoint.
+ */
+ if (control_position(current_position, ground_speed, _global_triplet)) {
+ _att_sp.timestamp = hrt_absolute_time();
+
+ /* lazily publish the setpoint only once available */
+ if (_attitude_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), _attitude_sp_pub, &_att_sp);
+
+ } else {
+ /* advertise and publish */
+ _attitude_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_att_sp);
+ }
+
+ }
+
+ }
+
+ perf_end(_loop_perf);
+ }
+
+ warnx("exiting.\n");
+
+ _control_task = -1;
+ _exit(0);
+}
+
+int
+FixedwingPositionControl::start()
+{
+ ASSERT(_control_task == -1);
+
+ /* start the task */
+ _control_task = task_spawn_cmd("fw_pos_control_l1",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 4048,
+ (main_t)&FixedwingPositionControl::task_main_trampoline,
+ nullptr);
+
+ if (_control_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+int fw_pos_control_l1_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ errx(1, "usage: fw_pos_control_l1 {start|stop|status}");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (l1_control::g_control != nullptr)
+ errx(1, "already running");
+
+ l1_control::g_control = new FixedwingPositionControl;
+
+ if (l1_control::g_control == nullptr)
+ errx(1, "alloc failed");
+
+ if (OK != l1_control::g_control->start()) {
+ delete l1_control::g_control;
+ l1_control::g_control = nullptr;
+ err(1, "start failed");
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (l1_control::g_control == nullptr)
+ errx(1, "not running");
+
+ delete l1_control::g_control;
+ l1_control::g_control = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (l1_control::g_control) {
+ errx(0, "running");
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warnx("unrecognized command");
+ return 1;
+}
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
new file mode 100644
index 000000000..d210ec712
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -0,0 +1,109 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file fw_pos_control_l1_params.c
+ *
+ * Parameters defined by the L1 position control task
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Controller parameters, accessible via MAVLink
+ *
+ */
+
+PARAM_DEFINE_FLOAT(FW_L1_PERIOD, 25.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f);
+
+
+PARAM_DEFINE_FLOAT(FW_LOITER_R, 50.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.7f);
+
+
+PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
+
+
+PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
diff --git a/src/modules/fw_pos_control_l1/module.mk b/src/modules/fw_pos_control_l1/module.mk
new file mode 100644
index 000000000..b00b9aa5a
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Fixedwing L1 position control application
+#
+
+MODULE_COMMAND = fw_pos_control_l1
+
+SRCS = fw_pos_control_l1_main.cpp \
+ fw_pos_control_l1_params.c
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index cbcd4adfb..7a5c2dab2 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -531,7 +531,7 @@ int mavlink_thread_main(int argc, char *argv[])
case 'b':
baudrate = strtoul(optarg, NULL, 10);
- if (baudrate == 0)
+ if (baudrate < 9600 || baudrate > 921600)
errx(1, "invalid baud rate '%s'", optarg);
break;
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 222d1f45f..7dd9e321f 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -102,6 +102,7 @@ struct vehicle_global_position_s hil_global_pos;
struct vehicle_attitude_s hil_attitude;
struct vehicle_gps_position_s hil_gps;
struct sensor_combined_s hil_sensors;
+struct battery_status_s hil_battery_status;
static orb_advert_t pub_hil_global_pos = -1;
static orb_advert_t pub_hil_attitude = -1;
static orb_advert_t pub_hil_gps = -1;
@@ -111,6 +112,12 @@ static orb_advert_t pub_hil_accel = -1;
static orb_advert_t pub_hil_mag = -1;
static orb_advert_t pub_hil_baro = -1;
static orb_advert_t pub_hil_airspeed = -1;
+static orb_advert_t pub_hil_battery = -1;
+
+/* packet counter */
+static int hil_counter = 0;
+static int hil_frames = 0;
+static uint64_t old_timestamp = 0;
static orb_advert_t cmd_pub = -1;
static orb_advert_t flow_pub = -1;
@@ -149,7 +156,8 @@ handle_message(mavlink_message_t *msg)
vcmd.param5 = cmd_mavlink.param5;
vcmd.param6 = cmd_mavlink.param6;
vcmd.param7 = cmd_mavlink.param7;
- vcmd.command = cmd_mavlink.command;
+ // XXX do proper translation
+ vcmd.command = (enum VEHICLE_CMD)cmd_mavlink.command;
vcmd.target_system = cmd_mavlink.target_system;
vcmd.target_component = cmd_mavlink.target_component;
vcmd.source_system = msg->sysid;
@@ -207,7 +215,7 @@ handle_message(mavlink_message_t *msg)
vcmd.param5 = 0;
vcmd.param6 = 0;
vcmd.param7 = 0;
- vcmd.command = MAV_CMD_DO_SET_MODE;
+ vcmd.command = VEHICLE_CMD_DO_SET_MODE;
vcmd.target_system = new_mode.target_system;
vcmd.target_component = MAV_COMP_ID_ALL;
vcmd.source_system = msg->sysid;
@@ -360,11 +368,6 @@ handle_message(mavlink_message_t *msg)
mavlink_hil_sensor_t imu;
mavlink_msg_hil_sensor_decode(msg, &imu);
- /* packet counter */
- static uint16_t hil_counter = 0;
- static uint16_t hil_frames = 0;
- static uint64_t old_timestamp = 0;
-
/* sensors general */
hil_sensors.timestamp = hrt_absolute_time();
@@ -391,9 +394,9 @@ handle_message(mavlink_message_t *msg)
hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16
/* adc */
- hil_sensors.adc_voltage_v[0] = 0;
- hil_sensors.adc_voltage_v[1] = 0;
- hil_sensors.adc_voltage_v[2] = 0;
+ hil_sensors.adc_voltage_v[0] = 0.0f;
+ hil_sensors.adc_voltage_v[1] = 0.0f;
+ hil_sensors.adc_voltage_v[2] = 0.0f;
/* magnetometer */
float mga2ga = 1.0e-3f;
@@ -506,6 +509,18 @@ handle_message(mavlink_message_t *msg)
pub_hil_sensors = orb_advertise(ORB_ID(sensor_combined), &hil_sensors);
}
+ /* fill in HIL battery status */
+ hil_battery_status.timestamp = hrt_absolute_time();
+ hil_battery_status.voltage_v = 11.1f;
+ hil_battery_status.current_a = 10.0f;
+
+ /* lazily publish the battery voltage */
+ if (pub_hil_battery > 0) {
+ orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);
+ } else {
+ pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
+ }
+
// increment counters
hil_counter++;
hil_frames++;
@@ -574,6 +589,7 @@ handle_message(mavlink_message_t *msg)
orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
}
+ hil_global_pos.valid = true;
hil_global_pos.lat = hil_state.lat;
hil_global_pos.lon = hil_state.lon;
hil_global_pos.alt = hil_state.alt / 1000.0f;
@@ -639,6 +655,18 @@ handle_message(mavlink_message_t *msg)
} else {
orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
}
+
+ /* fill in HIL battery status */
+ hil_battery_status.timestamp = hrt_absolute_time();
+ hil_battery_status.voltage_v = 11.1f;
+ hil_battery_status.current_a = 10.0f;
+
+ /* lazily publish the battery voltage */
+ if (pub_hil_battery > 0) {
+ orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);
+ } else {
+ pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
+ }
}
if (msg->msgid == MAVLINK_MSG_ID_MANUAL_CONTROL) {
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index d11a67fc6..cec2fdc43 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -99,6 +99,8 @@ struct listener {
uintptr_t arg;
};
+uint16_t cm_uint16_from_m_float(float m);
+
static void l_sensor_combined(const struct listener *l);
static void l_vehicle_attitude(const struct listener *l);
static void l_vehicle_gps_position(const struct listener *l);
@@ -150,6 +152,19 @@ static const struct listener listeners[] = {
static const unsigned n_listeners = sizeof(listeners) / sizeof(listeners[0]);
+uint16_t
+cm_uint16_from_m_float(float m)
+{
+ if (m < 0.0f) {
+ return 0;
+
+ } else if (m > 655.35f) {
+ return 65535;
+ }
+
+ return (uint16_t)(m * 100.0f);
+}
+
void
l_sensor_combined(const struct listener *l)
{
@@ -235,8 +250,10 @@ l_vehicle_gps_position(const struct listener *l)
/* 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;
@@ -247,10 +264,10 @@ l_vehicle_gps_position(const struct listener *l)
gps.lat,
gps.lon,
gps.alt,
- gps.eph_m * 1e2f, // from m to cm
- gps.epv_m * 1e2f, // from m to cm
+ cm_uint16_from_m_float(gps.eph_m),
+ cm_uint16_from_m_float(gps.epv_m),
gps.vel_m_s * 1e2f, // from m/s to cm/s
- cog_deg * 1e2f, // from rad to deg * 100
+ cog_deg * 1e2f, // from deg to deg * 100
gps.satellites_visible);
/* update SAT info every 10 seconds */
diff --git a/src/modules/mavlink/orb_topics.h b/src/modules/mavlink/orb_topics.h
index e2e630046..c5cd0d03e 100644
--- a/src/modules/mavlink/orb_topics.h
+++ b/src/modules/mavlink/orb_topics.h
@@ -65,6 +65,7 @@
#include <uORB/topics/telemetry_status.h>
#include <uORB/topics/debug_key_value.h>
#include <uORB/topics/airspeed.h>
+#include <uORB/topics/battery_status.h>
#include <drivers/drv_rc_input.h>
struct mavlink_subscriptions {
diff --git a/src/modules/mavlink/waypoints.c b/src/modules/mavlink/waypoints.c
index c6c2eac68..97472c233 100644
--- a/src/modules/mavlink/waypoints.c
+++ b/src/modules/mavlink/waypoints.c
@@ -246,47 +246,6 @@ void mavlink_wpm_send_waypoint_reached(uint16_t seq)
// FIXME TIMING usleep(paramClient->getParamValue("PROTOCOLDELAY"));
}
-//float mavlink_wpm_distance_to_segment(uint16_t seq, float x, float y, float z)
-//{
-// if (seq < wpm->size)
-// {
-// mavlink_mission_item_t *cur = waypoints->at(seq);
-//
-// const PxVector3 A(cur->x, cur->y, cur->z);
-// const PxVector3 C(x, y, z);
-//
-// // seq not the second last waypoint
-// if ((uint16_t)(seq+1) < wpm->size)
-// {
-// mavlink_mission_item_t *next = waypoints->at(seq+1);
-// const PxVector3 B(next->x, next->y, next->z);
-// const float r = (B-A).dot(C-A) / (B-A).lengthSquared();
-// if (r >= 0 && r <= 1)
-// {
-// const PxVector3 P(A + r*(B-A));
-// return (P-C).length();
-// }
-// else if (r < 0.f)
-// {
-// return (C-A).length();
-// }
-// else
-// {
-// return (C-B).length();
-// }
-// }
-// else
-// {
-// return (C-A).length();
-// }
-// }
-// else
-// {
-// // if (verbose) // printf("ERROR: index out of bounds\n");
-// }
-// return -1.f;
-//}
-
/*
* Calculate distance in global frame.
*
@@ -337,7 +296,7 @@ float mavlink_wpm_distance_to_point_local(uint16_t seq, float x, float y, float
float dy = (cur->y - y);
float dz = (cur->z - z);
- return sqrt(dx * dx + dy * dy + dz * dz);
+ return sqrtf(dx * dx + dy * dy + dz * dz);
} else {
return -1.0f;
@@ -348,6 +307,11 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
{
static uint16_t counter;
+ if (!global_pos->valid && !local_pos->xy_valid) {
+ /* nothing to check here, return */
+ return;
+ }
+
if (wpm->current_active_wp_id < wpm->size) {
float orbit;
@@ -421,15 +385,53 @@ void check_waypoints_reached(uint64_t now, const struct vehicle_global_position_
if (cur_wp->autocontinue) {
cur_wp->current = 0;
+ float navigation_lat = -1.0f;
+ float navigation_lon = -1.0f;
+ float navigation_alt = -1.0f;
+ int navigation_frame = -1;
+
+ /* initialize to current position in case we don't find a suitable navigation waypoint */
+ if (global_pos->valid) {
+ navigation_lat = global_pos->lat/1e7;
+ navigation_lon = global_pos->lon/1e7;
+ navigation_alt = global_pos->alt;
+ navigation_frame = MAV_FRAME_GLOBAL;
+ } else if (local_pos->xy_valid && local_pos->z_valid) {
+ navigation_lat = local_pos->x;
+ navigation_lon = local_pos->y;
+ navigation_alt = local_pos->z;
+ navigation_frame = MAV_FRAME_LOCAL_NED;
+ }
+
/* only accept supported navigation waypoints, skip unknown ones */
do {
+ /* pick up the last valid navigation waypoint, this will be one we hold on to after the mission */
+ if (wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_WAYPOINT ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TURNS ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_TIME ||
+ wpm->waypoints[wpm->current_active_wp_id].command == (int)MAV_CMD_NAV_LOITER_UNLIM) {
+
+ /* this is a navigation waypoint */
+ navigation_frame = cur_wp->frame;
+ navigation_lat = cur_wp->x;
+ navigation_lon = cur_wp->y;
+ navigation_alt = cur_wp->z;
+ }
if (wpm->current_active_wp_id == wpm->size - 1 && wpm->size > 1) {
/* the last waypoint was reached, if auto continue is
* activated keep the system loitering there.
*/
cur_wp->command = MAV_CMD_NAV_LOITER_UNLIM;
- cur_wp->param3 = 15.0f; // XXX magic number 15 m loiter radius
+ cur_wp->param3 = 20.0f; // XXX magic number 20 m loiter radius
+ cur_wp->frame = navigation_frame;
+ cur_wp->x = navigation_lat;
+ cur_wp->y = navigation_lon;
+ cur_wp->z = navigation_alt;
+ cur_wp->autocontinue = false;
+
+ /* we risk an endless loop for missions without navigation waypoints, abort. */
+ break;
} else {
if ((uint16_t)(wpm->current_active_wp_id + 1) < wpm->size)
@@ -484,11 +486,6 @@ int mavlink_waypoint_eventloop(uint64_t now, const struct vehicle_global_positio
}
}
- // Do NOT continously send the current WP, since we're not loosing messages
- // if (now - wpm->timestamp_last_send_setpoint > wpm->delay_setpoint && wpm->current_active_wp_id < wpm->size) {
- // mavlink_wpm_send_setpoint(wpm->current_active_wp_id);
- // }
-
check_waypoints_reached(now, global_position, local_position);
return OK;
@@ -500,115 +497,6 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
uint64_t now = mavlink_missionlib_get_system_timestamp();
switch (msg->msgid) {
-// case MAVLINK_MSG_ID_ATTITUDE:
-// {
-// if(msg->sysid == mavlink_system.sysid && wpm->current_active_wp_id < wpm->size)
-// {
-// mavlink_mission_item_t *wp = &(wpm->waypoints[wpm->current_active_wp_id]);
-// if(wp->frame == MAV_FRAME_LOCAL_ENU || wp->frame == MAV_FRAME_LOCAL_NED)
-// {
-// mavlink_attitude_t att;
-// mavlink_msg_attitude_decode(msg, &att);
-// float yaw_tolerance = wpm->accept_range_yaw;
-// //compare current yaw
-// if (att.yaw - yaw_tolerance >= 0.0f && att.yaw + yaw_tolerance < 2.f*FM_PI)
-// {
-// if (att.yaw - yaw_tolerance <= wp->param4 && att.yaw + yaw_tolerance >= wp->param4)
-// wpm->yaw_reached = true;
-// }
-// else if(att.yaw - yaw_tolerance < 0.0f)
-// {
-// float lowerBound = 360.0f + att.yaw - yaw_tolerance;
-// if (lowerBound < wp->param4 || wp->param4 < att.yaw + yaw_tolerance)
-// wpm->yaw_reached = true;
-// }
-// else
-// {
-// float upperBound = att.yaw + yaw_tolerance - 2.f*FM_PI;
-// if (att.yaw - yaw_tolerance < wp->param4 || wp->param4 < upperBound)
-// wpm->yaw_reached = true;
-// }
-// }
-// }
-// break;
-// }
-//
-// case MAVLINK_MSG_ID_LOCAL_POSITION_NED:
-// {
-// if(msg->sysid == mavlink_system.sysid && wpm->current_active_wp_id < wpm->size)
-// {
-// mavlink_mission_item_t *wp = &(wpm->waypoints[wpm->current_active_wp_id]);
-//
-// if(wp->frame == MAV_FRAME_LOCAL_ENU || MAV_FRAME_LOCAL_NED)
-// {
-// mavlink_local_position_ned_t pos;
-// mavlink_msg_local_position_ned_decode(msg, &pos);
-// //// if (debug) // printf("Received new position: x: %f | y: %f | z: %f\n", pos.x, pos.y, pos.z);
-//
-// wpm->pos_reached = false;
-//
-// // compare current position (given in message) with current waypoint
-// float orbit = wp->param1;
-//
-// float dist;
-//// if (wp->param2 == 0)
-//// {
-//// // FIXME segment distance
-//// //dist = mavlink_wpm_distance_to_segment(current_active_wp_id, pos.x, pos.y, pos.z);
-//// }
-//// else
-//// {
-// dist = mavlink_wpm_distance_to_point(wpm->current_active_wp_id, pos.x, pos.y, pos.z);
-//// }
-//
-// if (dist >= 0.f && dist <= orbit && wpm->yaw_reached)
-// {
-// wpm->pos_reached = true;
-// }
-// }
-// }
-// break;
-// }
-
-// case MAVLINK_MSG_ID_CMD: // special action from ground station
-// {
-// mavlink_cmd_t action;
-// mavlink_msg_cmd_decode(msg, &action);
-// if(action.target == mavlink_system.sysid)
-// {
-// // if (verbose) std::cerr << "Waypoint: received message with action " << action.action << std::endl;
-// switch (action.action)
-// {
-// // case MAV_ACTION_LAUNCH:
-// // // if (verbose) std::cerr << "Launch received" << std::endl;
-// // current_active_wp_id = 0;
-// // if (wpm->size>0)
-// // {
-// // setActive(waypoints[current_active_wp_id]);
-// // }
-// // else
-// // // if (verbose) std::cerr << "No launch, waypointList empty" << std::endl;
-// // break;
-//
-// // case MAV_ACTION_CONTINUE:
-// // // if (verbose) std::c
-// // err << "Continue received" << std::endl;
-// // idle = false;
-// // setActive(waypoints[current_active_wp_id]);
-// // break;
-//
-// // case MAV_ACTION_HALT:
-// // // if (verbose) std::cerr << "Halt received" << std::endl;
-// // idle = true;
-// // break;
-//
-// // default:
-// // // if (verbose) std::cerr << "Unknown action received with id " << action.action << ", no action taken" << std::endl;
-// // break;
-// }
-// }
-// break;
-// }
case MAVLINK_MSG_ID_MISSION_ACK: {
mavlink_mission_ack_t wpa;
@@ -619,26 +507,16 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
if (wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) {
if (wpm->current_wp_id == wpm->size - 1) {
-#ifdef MAVLINK_WPM_NO_PRINTF
- mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE");
-#else
- if (MAVLINK_WPM_VERBOSE) printf("Received ACK after having sent last waypoint, going to state MAVLINK_WPM_STATE_IDLE\n");
+ mavlink_missionlib_send_gcs_string("Got last WP ACK state -> IDLE");
-#endif
wpm->current_state = MAVLINK_WPM_STATE_IDLE;
wpm->current_wp_id = 0;
}
}
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
-
-#endif
}
break;
@@ -666,13 +544,8 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
}
}
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("NEW WP SET");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("New current waypoint %u\n", wpm->current_active_wp_id);
-#endif
wpm->yaw_reached = false;
wpm->pos_reached = false;
mavlink_wpm_send_waypoint_current(wpm->current_active_wp_id);
@@ -680,33 +553,16 @@ void mavlink_wpm_message_handler(const mavlink_message_t *msg, const struct vehi
wpm->timestamp_firstinside_orbit = 0;
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("Ignored MAVLINK_MSG_ID_MISSION_ITEM_SET_CURRENT: Index out of bounds\n");
-
-#endif
}
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE NOT IN IDLE STATE\n");
-#endif
}
} else {
-#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch");
-#else
-
- if (MAVLINK_WPM_VERBOSE) printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
-
-#endif
}
break;
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index 336523072..36dd370fb 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
@@ -193,7 +193,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
struct vehicle_local_position_setpoint_s local_pos_sp;
memset(&local_pos_sp, 0, sizeof(local_pos_sp));
struct vehicle_global_position_setpoint_s global_pos_sp;
- memset(&global_pos_sp, 0, sizeof(local_pos_sp));
+ memset(&global_pos_sp, 0, sizeof(global_pos_sp));
struct vehicle_global_velocity_setpoint_s global_vel_sp;
memset(&global_vel_sp, 0, sizeof(global_vel_sp));
@@ -212,17 +212,17 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
orb_advert_t global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &global_vel_sp);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
- bool global_pos_sp_reproject = false;
+ bool reset_mission_sp = false;
bool global_pos_sp_valid = false;
- bool local_pos_sp_valid = false;
- bool reset_sp_z = true;
- bool reset_sp_xy = true;
+ bool reset_man_sp_z = true;
+ bool reset_man_sp_xy = true;
bool reset_int_z = true;
bool reset_int_z_manual = false;
bool reset_int_xy = true;
bool was_armed = false;
- bool reset_integral = true;
- bool reset_auto_pos = true;
+ bool reset_auto_sp_xy = true;
+ bool reset_auto_sp_z = true;
+ bool reset_takeoff_sp = true;
hrt_abstime t_prev = 0;
const float alt_ctl_dz = 0.2f;
@@ -270,11 +270,11 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
/* use integral_limit_out = tilt_max / 2 */
float i_limit;
- if (params.xy_vel_i == 0.0f) {
+ if (params.xy_vel_i > 0.0f) {
i_limit = params.tilt_max / params.xy_vel_i / 2.0f;
} else {
- i_limit = 1.0f; // not used really
+ i_limit = 0.0f; // not used
}
pid_set_parameters(&(xy_vel_pids[i]), params.xy_vel_p, params.xy_vel_i, params.xy_vel_d, i_limit, params.tilt_max);
@@ -297,7 +297,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(vehicle_global_position_setpoint), global_pos_sp_sub, &global_pos_sp);
global_pos_sp_valid = true;
- global_pos_sp_reproject = true;
+ reset_mission_sp = true;
}
hrt_abstime t = hrt_absolute_time();
@@ -312,8 +312,11 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
if (control_mode.flag_armed && !was_armed) {
/* reset setpoints and integrals on arming */
- reset_sp_z = true;
- reset_sp_xy = true;
+ reset_man_sp_z = true;
+ reset_man_sp_xy = true;
+ reset_auto_sp_z = true;
+ reset_auto_sp_xy = true;
+ reset_takeoff_sp = true;
reset_int_z = true;
reset_int_xy = true;
}
@@ -348,8 +351,8 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
/* reset setpoints to current position if needed */
if (control_mode.flag_control_altitude_enabled) {
- if (reset_sp_z) {
- reset_sp_z = false;
+ if (reset_man_sp_z) {
+ reset_man_sp_z = false;
local_pos_sp.z = local_pos.z;
mavlink_log_info(mavlink_fd, "[mpc] reset alt sp: %.2f", (double) - local_pos_sp.z);
}
@@ -371,8 +374,8 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
}
if (control_mode.flag_control_position_enabled) {
- if (reset_sp_xy) {
- reset_sp_xy = false;
+ if (reset_man_sp_xy) {
+ reset_man_sp_xy = false;
local_pos_sp.x = local_pos.x;
local_pos_sp.y = local_pos.y;
pid_reset_integral(&xy_vel_pids[0]);
@@ -405,41 +408,45 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
}
}
+ /* copy yaw setpoint to vehicle_local_position_setpoint topic */
local_pos_sp.yaw = att_sp.yaw_body;
- /* local position setpoint is valid and can be used for loiter after position controlled mode */
- local_pos_sp_valid = control_mode.flag_control_position_enabled;
-
- reset_auto_pos = true;
+ /* local position setpoint is valid and can be used for auto loiter after position controlled mode */
+ reset_auto_sp_xy = !control_mode.flag_control_position_enabled;
+ reset_auto_sp_z = !control_mode.flag_control_altitude_enabled;
+ reset_takeoff_sp = true;
/* force reprojection of global setpoint after manual mode */
- global_pos_sp_reproject = true;
+ reset_mission_sp = true;
} else if (control_mode.flag_control_auto_enabled) {
/* AUTO mode, use global setpoint */
if (control_mode.auto_state == NAVIGATION_STATE_AUTO_READY) {
- reset_auto_pos = true;
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
} else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_TAKEOFF) {
- if (reset_auto_pos) {
+ if (reset_takeoff_sp) {
+ reset_takeoff_sp = false;
local_pos_sp.x = local_pos.x;
local_pos_sp.y = local_pos.y;
local_pos_sp.z = - params.takeoff_alt - params.takeoff_gap;
- local_pos_sp.yaw = att.yaw;
- local_pos_sp_valid = true;
att_sp.yaw_body = att.yaw;
- reset_auto_pos = false;
mavlink_log_info(mavlink_fd, "[mpc] takeoff sp: %.2f %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y, (double) - local_pos_sp.z);
}
+ reset_auto_sp_xy = false;
+ reset_auto_sp_z = true;
+
} else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_RTL) {
// TODO
- reset_auto_pos = true;
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
} else if (control_mode.auto_state == NAVIGATION_STATE_AUTO_MISSION) {
/* init local projection using local position ref */
if (local_pos.ref_timestamp != local_ref_timestamp) {
- global_pos_sp_reproject = true;
+ reset_mission_sp = true;
local_ref_timestamp = local_pos.ref_timestamp;
double lat_home = local_pos.ref_lat * 1e-7;
double lon_home = local_pos.ref_lon * 1e-7;
@@ -447,9 +454,9 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
mavlink_log_info(mavlink_fd, "[mpc] local pos ref: %.7f, %.7f", (double)lat_home, (double)lon_home);
}
- if (global_pos_sp_reproject) {
+ if (reset_mission_sp) {
+ reset_mission_sp = false;
/* update global setpoint projection */
- global_pos_sp_reproject = false;
if (global_pos_sp_valid) {
/* global position setpoint valid, use it */
@@ -464,40 +471,50 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
} else {
local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude;
}
-
- local_pos_sp.yaw = global_pos_sp.yaw;
att_sp.yaw_body = global_pos_sp.yaw;
mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", (double)sp_lat, sp_lon, (double)local_pos_sp.x, (double)local_pos_sp.y);
} else {
- if (!local_pos_sp_valid) {
+ if (reset_auto_sp_xy) {
+ reset_auto_sp_xy = false;
/* local position setpoint is invalid,
* use current position as setpoint for loiter */
local_pos_sp.x = local_pos.x;
local_pos_sp.y = local_pos.y;
- local_pos_sp.z = local_pos.z;
local_pos_sp.yaw = att.yaw;
- local_pos_sp_valid = true;
+ }
+
+ if (reset_auto_sp_z) {
+ reset_auto_sp_z = false;
+ local_pos_sp.z = local_pos.z;
}
mavlink_log_info(mavlink_fd, "[mpc] no global pos sp, loiter: %.2f, %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y);
}
}
- reset_auto_pos = true;
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
+ }
+
+ if (control_mode.auto_state != NAVIGATION_STATE_AUTO_TAKEOFF) {
+ reset_takeoff_sp = true;
}
if (control_mode.auto_state != NAVIGATION_STATE_AUTO_MISSION) {
- global_pos_sp_reproject = true;
+ reset_mission_sp = true;
}
+ /* copy yaw setpoint to vehicle_local_position_setpoint topic */
+ local_pos_sp.yaw = att_sp.yaw_body;
+
/* reset setpoints after AUTO mode */
- reset_sp_xy = true;
- reset_sp_z = true;
+ reset_man_sp_xy = true;
+ reset_man_sp_z = true;
} else {
- /* no control, loiter or stay on ground */
+ /* no control (failsafe), loiter or stay on ground */
if (local_pos.landed) {
/* landed: move setpoint down */
/* in air: hold altitude */
@@ -508,27 +525,30 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
mavlink_log_info(mavlink_fd, "[mpc] landed, set alt: %.2f", (double) - local_pos_sp.z);
}
- reset_sp_z = true;
+ reset_man_sp_z = true;
} else {
/* in air: hold altitude */
- if (reset_sp_z) {
- reset_sp_z = false;
+ if (reset_man_sp_z) {
+ reset_man_sp_z = false;
local_pos_sp.z = local_pos.z;
mavlink_log_info(mavlink_fd, "[mpc] set loiter alt: %.2f", (double) - local_pos_sp.z);
}
+
+ reset_auto_sp_z = false;
}
if (control_mode.flag_control_position_enabled) {
- if (reset_sp_xy) {
- reset_sp_xy = false;
+ if (reset_man_sp_xy) {
+ reset_man_sp_xy = false;
local_pos_sp.x = local_pos.x;
local_pos_sp.y = local_pos.y;
local_pos_sp.yaw = att.yaw;
- local_pos_sp_valid = true;
att_sp.yaw_body = att.yaw;
mavlink_log_info(mavlink_fd, "[mpc] set loiter pos: %.2f %.2f", (double)local_pos_sp.x, (double)local_pos_sp.y);
}
+
+ reset_auto_sp_xy = false;
}
}
@@ -540,7 +560,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
global_vel_sp.vz = pid_calculate(&z_pos_pid, local_pos_sp.z, local_pos.z, local_pos.vz - sp_move_rate[2], dt) + sp_move_rate[2];
} else {
- reset_sp_z = true;
+ reset_man_sp_z = true;
global_vel_sp.vz = 0.0f;
}
@@ -558,7 +578,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
}
} else {
- reset_sp_xy = true;
+ reset_man_sp_xy = true;
global_vel_sp.vx = 0.0f;
global_vel_sp.vy = 0.0f;
}
@@ -640,12 +660,13 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
} else {
/* position controller disabled, reset setpoints */
- reset_sp_z = true;
- reset_sp_xy = true;
+ reset_man_sp_z = true;
+ reset_man_sp_xy = true;
reset_int_z = true;
reset_int_xy = true;
- global_pos_sp_reproject = true;
- reset_auto_pos = true;
+ reset_mission_sp = true;
+ reset_auto_sp_xy = true;
+ reset_auto_sp_z = true;
}
/* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
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 932f61088..10007bf96 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -259,7 +259,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.ref_timestamp = hrt_absolute_time();
local_pos.z_valid = true;
local_pos.v_z_valid = true;
- local_pos.global_z = true;
+ local_pos.z_global = true;
}
}
}
@@ -597,7 +597,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.timestamp = t;
local_pos.xy_valid = can_estimate_xy && gps_valid;
local_pos.v_xy_valid = can_estimate_xy;
- local_pos.global_xy = local_pos.xy_valid && gps_valid; // will make sense when local position sources (e.g. vicon) will be implemented
+ local_pos.xy_global = local_pos.xy_valid && gps_valid; // will make sense when local position sources (e.g. vicon) will be implemented
local_pos.x = x_est[0];
local_pos.vx = x_est[1];
local_pos.y = y_est[0];
@@ -610,9 +610,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos);
/* publish global position */
- global_pos.valid = local_pos.global_xy;
+ global_pos.valid = local_pos.xy_global;
- if (local_pos.global_xy) {
+ if (local_pos.xy_global) {
double est_lat, est_lon;
map_projection_reproject(local_pos.x, local_pos.y, &est_lat, &est_lon);
global_pos.lat = (int32_t)(est_lat * 1e7);
@@ -630,7 +630,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
global_pos.relative_alt = -local_pos.z;
}
- if (local_pos.global_z) {
+ if (local_pos.z_global) {
global_pos.alt = local_pos.ref_alt - local_pos.z;
}
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 617b536f4..5c621cfb2 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -286,7 +286,7 @@ controls_tick() {
* requested override.
*
*/
- if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) > RC_CHANNEL_HIGH_THRESH))
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) < RC_CHANNEL_LOW_THRESH))
override = true;
if (override) {
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index 206e27db5..433976656 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -243,28 +243,35 @@ dsm_init(const char *device)
void
dsm_bind(uint16_t cmd, int pulses)
{
+#if !defined(CONFIG_ARCH_BOARD_PX4IO_V1) && !defined(CONFIG_ARCH_BOARD_PX4IO_V2)
+ #warning DSM BIND NOT IMPLEMENTED ON UNKNOWN PLATFORM
+#else
const uint32_t usart1RxAsOutp =
GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN10;
if (dsm_fd < 0)
return;
-#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
- // XXX implement
- #warning DSM BIND NOT IMPLEMENTED ON PX4IO V2
-#else
switch (cmd) {
case dsm_bind_power_down:
/*power down DSM satellite*/
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
POWER_RELAY1(0);
+#else /* CONFIG_ARCH_BOARD_PX4IO_V2 */
+ POWER_SPEKTRUM(0);
+#endif
break;
case dsm_bind_power_up:
/*power up DSM satellite*/
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
POWER_RELAY1(1);
+#else /* CONFIG_ARCH_BOARD_PX4IO_V2 */
+ POWER_SPEKTRUM(1);
+#endif
dsm_guess_format(true);
break;
@@ -387,8 +394,10 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
values[channel] = value;
}
- if (dsm_channel_shift == 11)
+ if (dsm_channel_shift == 11) {
+ /* Set the 11-bit data indicator */
*num_values |= 0x8000;
+ }
/*
* XXX Note that we may be in failsafe here; we need to work out how to detect that.
@@ -412,7 +421,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values)
* Upon receiving a full dsm frame we attempt to decode it.
*
* @param[out] values pointer to per channel array of decoded values
- * @param[out] num_values pointer to number of raw channel values returned
+ * @param[out] num_values pointer to number of raw channel values returned, high order bit 0:10 bit data, 1:11 bit data
* @return true=decoded raw channel values updated, false=no update
*/
bool
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 0edd91b24..30aff7d20 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -221,7 +221,7 @@ mixer_tick(void)
}
/* do the calculations during the ramp for all at once */
- if(esc_state == ESC_RAMP) {
+ if (esc_state == ESC_RAMP) {
ramp_promille = (1000*(hrt_elapsed_time(&esc_init_time)-ESC_INIT_TIME_US))/ESC_RAMP_TIME_US;
}
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index f5fa0ba75..0e2cd1689 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -165,11 +165,13 @@
#define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */
#define PX4IO_P_SETUP_PWM_ALTRATE 4 /* 'high' PWM frame output rate in Hz */
+#if defined(CONFIG_ARCH_BOARD_PX4IO_V1) || defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
#define PX4IO_P_SETUP_RELAYS 5 /* bitmask of relay/switch outputs, 0 = off, 1 = on */
#define PX4IO_P_SETUP_RELAYS_POWER1 (1<<0) /* hardware rev [1] power relay 1 */
#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 */
+#endif
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* hardware rev [1] battery voltage correction factor (float) */
#define PX4IO_P_SETUP_VSERVO_SCALE 6 /* hardware rev [2] servo voltage correction factor (float) */
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 11f4d053d..66c4ca906 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -100,7 +100,9 @@ extern uint16_t r_page_servo_idle[]; /* PX4IO_PAGE_IDLE_PWM */
#define r_setup_pwm_rates r_page_setup[PX4IO_P_SETUP_PWM_RATES]
#define r_setup_pwm_defaultrate r_page_setup[PX4IO_P_SETUP_PWM_DEFAULTRATE]
#define r_setup_pwm_altrate r_page_setup[PX4IO_P_SETUP_PWM_ALTRATE]
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
#define r_setup_relays r_page_setup[PX4IO_P_SETUP_RELAYS]
+#endif
#define r_control_values (&r_page_controls[0])
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 30ef0ccea..9d9ef7c6d 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -145,7 +145,9 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_PWM_RATES] = 0,
[PX4IO_P_SETUP_PWM_DEFAULTRATE] = 50,
[PX4IO_P_SETUP_PWM_ALTRATE] = 200,
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
[PX4IO_P_SETUP_RELAYS] = 0,
+#endif
#ifdef ADC_VSERVO
[PX4IO_P_SETUP_VSERVO_SCALE] = 10000,
#else
@@ -462,22 +464,16 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
pwm_configure_rates(r_setup_pwm_rates, r_setup_pwm_defaultrate, value);
break;
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
case PX4IO_P_SETUP_RELAYS:
value &= PX4IO_P_SETUP_RELAYS_VALID;
r_setup_relays = value;
-#ifdef POWER_RELAY1
POWER_RELAY1((value & PX4IO_P_SETUP_RELAYS_POWER1) ? 1 : 0);
-#endif
-#ifdef POWER_RELAY2
POWER_RELAY2((value & PX4IO_P_SETUP_RELAYS_POWER2) ? 1 : 0);
-#endif
-#ifdef POWER_ACC1
POWER_ACC1((value & PX4IO_P_SETUP_RELAYS_ACC1) ? 1 : 0);
-#endif
-#ifdef POWER_ACC2
POWER_ACC2((value & PX4IO_P_SETUP_RELAYS_ACC2) ? 1 : 0);
-#endif
break;
+#endif
case PX4IO_P_SETUP_VBATT_SCALE:
r_page_setup[PX4IO_P_SETUP_VBATT_SCALE] = value;
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index e83fb7dd3..ec8033202 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -1046,6 +1046,9 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat;
log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon;
log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
+ log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
+ log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
+ log_msg.body.log_LPOS.landed = buf.local_pos.landed;
LOGBUFFER_WRITE_AND_COUNT(LPOS);
}
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 1343bb3d0..0e88da054 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -109,6 +109,9 @@ struct log_LPOS_s {
int32_t ref_lat;
int32_t ref_lon;
float ref_alt;
+ uint8_t xy_flags;
+ uint8_t z_flags;
+ uint8_t landed;
};
/* --- LPSP - LOCAL POSITION SETPOINT --- */
@@ -278,7 +281,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
- LOG_FORMAT(LPOS, "ffffffLLf", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt"),
+ LOG_FORMAT(LPOS, "ffffffLLfBBB", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt,XYFlags,ZFlags,Landed"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 992abf2cc..4d719e0e1 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -164,9 +164,10 @@ PARAM_DEFINE_FLOAT(RC15_MAX, 2000);
PARAM_DEFINE_FLOAT(RC15_REV, 1.0f);
PARAM_DEFINE_FLOAT(RC15_DZ, 0.0f);
-
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
-PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */
+#endif
+PARAM_DEFINE_INT32(RC_DSM_BIND, -1); /* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind */
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
@@ -174,7 +175,8 @@ PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */
/* PX4IOAR: 0.00838095238 */
/* FMU standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659 */
-PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f));
+/* FMU with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) */
+PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.00459340659f);
#endif
PARAM_DEFINE_INT32(RC_MAP_ROLL, 1);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index e98c4d548..085da905c 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1516,8 +1516,7 @@ Sensors::task_main()
{
/* inform about start */
- printf("[sensors] Initializing..\n");
- fflush(stdout);
+ warnx("Initializing..");
/* start individual sensors */
accel_init();
diff --git a/src/modules/systemlib/mixer/mixer.cpp b/src/modules/systemlib/mixer/mixer.cpp
index df0dfe838..b1bb1a66d 100644
--- a/src/modules/systemlib/mixer/mixer.cpp
+++ b/src/modules/systemlib/mixer/mixer.cpp
@@ -142,6 +142,22 @@ NullMixer *
NullMixer::from_text(const char *buf, unsigned &buflen)
{
NullMixer *nm = nullptr;
+ const char *end = buf + buflen;
+
+ /* enforce that the mixer ends with space or a new line */
+ for (int i = buflen - 1; i >= 0; i--) {
+ if (buf[i] == '\0')
+ continue;
+
+ /* require a space or newline at the end of the buffer, fail on printable chars */
+ if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
+ /* found a line ending or space, so no split symbols / numbers. good. */
+ break;
+ } else {
+ return nm;
+ }
+
+ }
if ((buflen >= 2) && (buf[0] == 'Z') && (buf[1] == ':')) {
nm = new NullMixer;
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 8ded0b05c..2446cc3fb 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -181,6 +181,23 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
char geomname[8];
int s[4];
int used;
+ const char *end = buf + buflen;
+
+ /* enforce that the mixer ends with space or a new line */
+ for (int i = buflen - 1; i >= 0; i--) {
+ if (buf[i] == '\0')
+ continue;
+
+ /* require a space or newline at the end of the buffer, fail on printable chars */
+ if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
+ /* found a line ending or space, so no split symbols / numbers. good. */
+ break;
+ } else {
+ debug("simple parser rejected: No newline / space at end of buf. (#%d/%d: 0x%02x)", i, buflen-1, buf[i]);
+ return nullptr;
+ }
+
+ }
if (sscanf(buf, "R: %s %d %d %d %d%n", geomname, &s[0], &s[1], &s[2], &s[3], &used) != 5) {
debug("multirotor parse failed on '%s'", buf);
diff --git a/src/modules/systemlib/mixer/mixer_simple.cpp b/src/modules/systemlib/mixer/mixer_simple.cpp
index 07dc5f37f..c8434f991 100644
--- a/src/modules/systemlib/mixer/mixer_simple.cpp
+++ b/src/modules/systemlib/mixer/mixer_simple.cpp
@@ -55,7 +55,7 @@
#include "mixer.h"
#define debug(fmt, args...) do { } while(0)
-//#define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0)
+// #define debug(fmt, args...) do { printf("[mixer] " fmt "\n", ##args); } while(0)
SimpleMixer::SimpleMixer(ControlCallback control_cb,
uintptr_t cb_handle,
@@ -98,14 +98,17 @@ SimpleMixer::parse_output_scaler(const char *buf, unsigned &buflen, mixer_scaler
{
int ret;
int s[5];
+ int n = -1;
buf = findtag(buf, buflen, 'O');
- if ((buf == nullptr) || (buflen < 12))
+ if ((buf == nullptr) || (buflen < 12)) {
+ debug("output parser failed finding tag, ret: '%s'", buf);
return -1;
+ }
- if ((ret = sscanf(buf, "O: %d %d %d %d %d",
- &s[0], &s[1], &s[2], &s[3], &s[4])) != 5) {
- debug("scaler parse failed on '%s' (got %d)", buf, ret);
+ if ((ret = sscanf(buf, "O: %d %d %d %d %d %n",
+ &s[0], &s[1], &s[2], &s[3], &s[4], &n)) != 5) {
+ debug("out scaler parse failed on '%s' (got %d, consumed %d)", buf, ret, n);
return -1;
}
skipline(buf, buflen);
@@ -126,8 +129,10 @@ SimpleMixer::parse_control_scaler(const char *buf, unsigned &buflen, mixer_scale
int s[5];
buf = findtag(buf, buflen, 'S');
- if ((buf == nullptr) || (buflen < 16))
+ if ((buf == nullptr) || (buflen < 16)) {
+ debug("contorl parser failed finding tag, ret: '%s'", buf);
return -1;
+ }
if (sscanf(buf, "S: %u %u %d %d %d %d %d",
&u[0], &u[1], &s[0], &s[1], &s[2], &s[3], &s[4]) != 7) {
@@ -156,6 +161,22 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c
int used;
const char *end = buf + buflen;
+ /* enforce that the mixer ends with space or a new line */
+ for (int i = buflen - 1; i >= 0; i--) {
+ if (buf[i] == '\0')
+ continue;
+
+ /* require a space or newline at the end of the buffer, fail on printable chars */
+ if (buf[i] == ' ' || buf[i] == '\n' || buf[i] == '\r') {
+ /* found a line ending or space, so no split symbols / numbers. good. */
+ break;
+ } else {
+ debug("simple parser rejected: No newline / space at end of buf. (#%d/%d: 0x%02x)", i, buflen-1, buf[i]);
+ goto out;
+ }
+
+ }
+
/* get the base info for the mixer */
if (sscanf(buf, "M: %u%n", &inputs, &used) != 1) {
debug("simple parse failed on '%s'", buf);
@@ -173,22 +194,27 @@ SimpleMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handle, c
mixinfo->control_count = inputs;
- if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler))
+ if (parse_output_scaler(end - buflen, buflen, mixinfo->output_scaler)) {
+ debug("simple mixer parser failed parsing out scaler tag, ret: '%s'", buf);
goto out;
+ }
for (unsigned i = 0; i < inputs; i++) {
if (parse_control_scaler(end - buflen, buflen,
mixinfo->controls[i].scaler,
mixinfo->controls[i].control_group,
- mixinfo->controls[i].control_index))
+ mixinfo->controls[i].control_index)) {
+ debug("simple mixer parser failed parsing ctrl scaler tag, ret: '%s'", buf);
goto out;
+ }
+
}
sm = new SimpleMixer(control_cb, cb_handle, mixinfo);
if (sm != nullptr) {
mixinfo = nullptr;
- debug("loaded mixer with %d inputs", inputs);
+ debug("loaded mixer with %d input(s)", inputs);
} else {
debug("could not allocate memory for mixer");
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index c69de52b7..ccdb2ea38 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -48,6 +48,7 @@
#include <unistd.h>
#include <systemlib/err.h>
#include <errno.h>
+#include <semaphore.h>
#include <sys/stat.h>
@@ -95,18 +96,20 @@ ORB_DEFINE(parameter_update, struct parameter_update_s);
/** parameter update topic handle */
static orb_advert_t param_topic = -1;
+static sem_t param_sem = { .semcount = 1 };
+
/** lock the parameter store */
static void
param_lock(void)
{
- /* XXX */
+ //do {} while (sem_wait(&param_sem) != 0);
}
/** unlock the parameter store */
static void
param_unlock(void)
{
- /* XXX */
+ //sem_post(&param_sem);
}
/** assert that the parameter store is locked */
@@ -506,29 +509,59 @@ int
param_save_default(void)
{
int result;
+ unsigned retries = 0;
/* delete the file in case it exists */
struct stat buffer;
if (stat(param_get_default_file(), &buffer) == 0) {
- result = unlink(param_get_default_file());
+
+ do {
+ result = unlink(param_get_default_file());
+ if (result != 0) {
+ retries++;
+ usleep(1000 * retries);
+ }
+ } while (result != OK && retries < 10);
+
if (result != OK)
warnx("unlinking file %s failed.", param_get_default_file());
}
/* create the file */
- int fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL);
+ int fd;
+
+ do {
+ /* do another attempt in case the unlink call is not synced yet */
+ fd = open(param_get_default_file(), O_WRONLY | O_CREAT | O_EXCL);
+ if (fd < 0) {
+ retries++;
+ usleep(1000 * retries);
+ }
+
+ } while (fd < 0 && retries < 10);
if (fd < 0) {
+
warn("opening '%s' for writing failed", param_get_default_file());
return fd;
}
- result = param_export(fd, false);
+ do {
+ result = param_export(fd, false);
+
+ if (result != OK) {
+ retries++;
+ usleep(1000 * retries);
+ }
+
+ } while (result != 0 && retries < 10);
+
+
close(fd);
- if (result != 0) {
+ if (result != OK) {
warn("error exporting parameters to '%s'", param_get_default_file());
- unlink(param_get_default_file());
+ (void)unlink(param_get_default_file());
return result;
}
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 739503ed4..77c952f52 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -167,20 +167,26 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
d = 0.0f;
}
- // Calculate the error integral and check for saturation
- i = pid->integral + (error * dt);
-
- if ((pid->limit > SIGMA && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) ||
- fabsf(i) > pid->intmax) {
- i = pid->integral; // If saturated then do not update integral value
- pid->saturated = 1;
+ if (pid->ki > 0.0f) {
+ // Calculate the error integral and check for saturation
+ i = pid->integral + (error * dt);
+
+ if ((pid->limit > SIGMA && (fabsf((error * pid->kp) + (i * pid->ki) + (d * pid->kd)) > pid->limit)) ||
+ fabsf(i) > pid->intmax) {
+ i = pid->integral; // If saturated then do not update integral value
+ pid->saturated = 1;
+
+ } else {
+ if (!isfinite(i)) {
+ i = 0.0f;
+ }
- } else {
- if (!isfinite(i)) {
- i = 0.0f;
+ pid->integral = i;
+ pid->saturated = 0;
}
- pid->integral = i;
+ } else {
+ i = 0.0f;
pid->saturated = 0;
}
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index 31ff014de..e6e4743c6 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -86,7 +86,8 @@ enum VEHICLE_CMD
VEHICLE_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
VEHICLE_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
VEHICLE_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- VEHICLE_CMD_ENUM_END=401, /* | */
+ VEHICLE_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ VEHICLE_CMD_ENUM_END=501, /* | */
};
/**
@@ -119,7 +120,7 @@ struct vehicle_command_s
float param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
float param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
float param7; /**< Parameter 7, as defined by MAVLink VEHICLE_CMD enum. */
- uint16_t command; /**< Command ID, as defined MAVLink by VEHICLE_CMD enum. */
+ enum VEHICLE_CMD command; /**< Command ID, as defined MAVLink by VEHICLE_CMD enum. */
uint8_t target_system; /**< System which should execute the command */
uint8_t target_component; /**< Component which should execute the command, 0 for all components */
uint8_t source_system; /**< System sending the command */
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 0a7fb4e9d..1639a08c2 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -56,9 +56,9 @@
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 */
+ int32_t lat; /**< Latitude in 1E-7 degrees */
+ int32_t lon; /**< Longitude in 1E-7 degrees */
+ int32_t alt; /**< Altitude in 1E-3 meters (millimeters) above MSL */
uint64_t timestamp_variance;
float s_variance_m_s; /**< speed accuracy estimate m/s */
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index 31a0e632b..427153782 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -70,8 +70,8 @@ struct vehicle_local_position_s
/* Heading */
float yaw;
/* Reference position in GPS / WGS84 frame */
- bool global_xy; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */
- bool global_z; /**< true if z is valid and has valid global reference (ref_alt) */
+ bool xy_global; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */
+ bool z_global; /**< true if z is valid and has valid global reference (ref_alt) */
uint64_t ref_timestamp; /**< Time when reference position was set */
int32_t ref_lat; /**< Reference point latitude in 1E7 degrees */
int32_t ref_lon; /**< Reference point longitude in 1E7 degrees */