From 29b0678d841666000fd67cc955dba5cf3cc980c5 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 6 Feb 2014 11:56:01 +0100 Subject: [PATCH 01/76] navigator: forbid READY - > RTL transition --- src/modules/navigator/navigator_main.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 5139ae6cd2..abd7119f78 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -689,7 +689,7 @@ Navigator::task_main() if (_vstatus.return_switch == RETURN_SWITCH_RETURN) { /* switch to RTL if not already landed after RTL and home position set */ if (!(_rtl_state == RTL_STATE_DESCEND && - (myState == NAV_STATE_READY || myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) && + (myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) && _vstatus.condition_home_position_valid) { dispatch(EVENT_RTL_REQUESTED); } @@ -748,7 +748,7 @@ Navigator::task_main() case NAV_STATE_RTL: if (!(_rtl_state == RTL_STATE_DESCEND && - (myState == NAV_STATE_READY || myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) && + (myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) && _vstatus.condition_home_position_valid) { dispatch(EVENT_RTL_REQUESTED); } @@ -756,9 +756,7 @@ Navigator::task_main() break; case NAV_STATE_LAND: - if (myState != NAV_STATE_READY) { - dispatch(EVENT_LAND_REQUESTED); - } + dispatch(EVENT_LAND_REQUESTED); break; From 1d40582cc0301f0af330fe69ee63aa8e3d301214 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 6 Feb 2014 12:42:20 +0100 Subject: [PATCH 02/76] navigator: forbid READY - > RTL transition fix --- src/modules/navigator/navigator_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index abd7119f78..6f0fec9179 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -965,7 +965,7 @@ StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_READY}, /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_READY}, /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION}, - /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL}, + /* EVENT_RTL_REQUESTED */ {NO_ACTION, NAV_STATE_READY}, /* EVENT_LAND_REQUESTED */ {NO_ACTION, NAV_STATE_READY}, /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_READY}, /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_READY}, From 6631ecf04a0592c816dfb832fa928a95877184d9 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 4 Feb 2014 11:45:35 +0100 Subject: [PATCH 03/76] commander: reset blink_msg_end when blink message completed to set normal LED status immediately --- src/modules/commander/commander_helper.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index 033e7dc88e..04624275f9 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -161,6 +161,7 @@ int blink_msg_state() return 0; } else if (hrt_absolute_time() > blink_msg_end) { + blink_msg_end = 0; return 2; } else { From 855944fb2eab33074537b5ccfc82e2462b662b5b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 11 Feb 2014 00:24:40 +0100 Subject: [PATCH 04/76] commander: beeps and blinks cleanup --- .../commander/accelerometer_calibration.cpp | 2 +- .../commander/airspeed_calibration.cpp | 2 +- src/modules/commander/commander.cpp | 46 ++++------ src/modules/commander/commander_helper.cpp | 86 +++++++++++-------- src/modules/commander/commander_helper.h | 14 +-- 5 files changed, 76 insertions(+), 74 deletions(-) diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index 36b75dd58a..1cbdf9bf85 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -311,7 +311,7 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float (double)accel_ref[orient][2]); data_collected[orient] = true; - tune_neutral(); + tune_neutral(true); } close(sensor_combined_sub); diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 1809f96888..6039d92a76 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -142,7 +142,7 @@ int do_airspeed_calibration(int mavlink_fd) } mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name); - tune_neutral(); + tune_neutral(true); close(diff_pres_sub); return OK; diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index c039b85737..193a7473eb 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1101,7 +1101,7 @@ int commander_thread_main(int argc, char *argv[]) /* mark home position as set */ status.condition_home_position_valid = true; - tune_positive(); + tune_positive(true); } } @@ -1196,8 +1196,9 @@ int commander_thread_main(int argc, char *argv[]) /* evaluate the main state machine according to mode switches */ res = set_main_state_rc(&status); + /* play tune on mode change only if armed, blink LED always */ if (res == TRANSITION_CHANGED) { - tune_positive(); + tune_positive(armed.armed); } else if (res == TRANSITION_DENIED) { /* DENIED here indicates bug in the commander */ @@ -1253,7 +1254,7 @@ int commander_thread_main(int argc, char *argv[]) /* flight termination in manual mode if assisted switch is on easy position */ if (!status.is_rotary_wing && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch > STICK_ON_OFF_LIMIT) { if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) { - tune_positive(); + tune_positive(armed.armed); } } @@ -1308,21 +1309,18 @@ int commander_thread_main(int argc, char *argv[]) /* play arming and battery warning tunes */ if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available && safety.safety_off))) { /* play tune when armed */ - if (tune_arm() == OK) - arm_tune_played = true; + set_tune(TONE_ARMING_WARNING_TUNE); } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW) { /* play tune on battery warning */ - if (tune_low_bat() == OK) - battery_tune_played = true; + set_tune(TONE_BATTERY_WARNING_SLOW_TUNE); } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) { /* play tune on battery critical */ - if (tune_critical_bat() == OK) - battery_tune_played = true; + set_tune(TONE_BATTERY_WARNING_FAST_TUNE); } else if (battery_tune_played) { - tune_stop(); + set_tune(TONE_STOP_TUNE); battery_tune_played = false; } @@ -1693,15 +1691,9 @@ print_reject_mode(struct vehicle_status_s *status, const char *msg) sprintf(s, "#audio: REJECT %s", msg); mavlink_log_critical(mavlink_fd, s); - // only buzz if armed, because else we're driving people nuts indoors - // they really need to look at the leds as well. - if (status->arming_state == ARMING_STATE_ARMED) { - tune_negative(); - } else { - - // Always show the led indication - led_negative(); - } + /* only buzz if armed, because else we're driving people nuts indoors + they really need to look at the leds as well. */ + tune_negative(armed.armed); } } @@ -1715,7 +1707,7 @@ print_reject_arm(const char *msg) char s[80]; sprintf(s, "#audio: %s", msg); mavlink_log_critical(mavlink_fd, s); - tune_negative(); + tune_negative(true); } } @@ -1723,27 +1715,27 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul { switch (result) { case VEHICLE_CMD_RESULT_ACCEPTED: - tune_positive(); + tune_positive(true); break; case VEHICLE_CMD_RESULT_DENIED: mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd.command); - tune_negative(); + tune_negative(true); break; case VEHICLE_CMD_RESULT_FAILED: mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd.command); - tune_negative(); + tune_negative(true); break; case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED: mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd.command); - tune_negative(); + tune_negative(true); break; case VEHICLE_CMD_RESULT_UNSUPPORTED: mavlink_log_critical(mavlink_fd, "#audio: command unsupported: %u", cmd.command); - tune_negative(); + tune_negative(true); break; default: @@ -1883,9 +1875,9 @@ void *commander_low_prio_loop(void *arg) } if (calib_ret == OK) - tune_positive(); + tune_positive(true); else - tune_negative(); + tune_negative(true); arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed); diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index 04624275f9..265c0134cb 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #include @@ -82,10 +83,21 @@ bool is_rotary_wing(const struct vehicle_status_s *current_status) } static int buzzer; -static hrt_abstime blink_msg_end; +static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message +static hrt_abstime tune_end = 0; // end time of currently played tune, 0 for repeating tunes or silence +static int tune_current = 0; // currently playing tune, can be interrupted after tune_end +static int tune_durations[TONE_NUMBER_OF_TUNES]; int buzzer_init() { + tune_end = 0; + tune_current = 0; + memset(tune_durations, 0, sizeof(tune_durations)); + tune_durations[TONE_NOTIFY_POSITIVE_TUNE] = 700000; + tune_durations[TONE_NOTIFY_NEGATIVE_TUNE] = 700000; + tune_durations[TONE_NOTIFY_NEUTRAL_TUNE] = 700000; + tune_durations[TONE_ARMING_WARNING_TUNE] = 3000000; + buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY); if (buzzer < 0) { @@ -93,6 +105,8 @@ int buzzer_init() return ERROR; } + ioctl(buzzer, TONE_SET_ALARM, TONE_STOP_TUNE); + return OK; } @@ -101,58 +115,60 @@ void buzzer_deinit() close(buzzer); } -void tune_error() -{ - ioctl(buzzer, TONE_SET_ALARM, TONE_ERROR_TUNE); +void set_tune(int tune) { + int new_tune_duration = tune_durations[tune]; + /* don't interrupt currently playing non-repeating tune by repeating */ + if (tune_end == 0 || new_tune_duration > 0 || hrt_absolute_time() > tune_end) { + /* allow interrupting current non-repeating tune by the same tune */ + if (tune != tune_current || new_tune_duration > 0) { + ioctl(buzzer, TONE_SET_ALARM, tune); + } + tune_current = tune; + if (new_tune_duration > 0) { + tune_end = hrt_absolute_time() + new_tune_duration; + } else { + tune_end = 0; + } + } } -void tune_positive() +/** + * Blink green LED and play positive tune (if use_busser == true). + */ +void tune_positive(bool use_buzzer) { 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); + if (use_buzzer) { + set_tune(TONE_NOTIFY_POSITIVE_TUNE); + } } -void tune_neutral() +/** + * Blink white LED and play neutral tune (if use_busser == true). + */ +void tune_neutral(bool use_buzzer) { 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); + if (use_buzzer) { + set_tune(TONE_NOTIFY_NEUTRAL_TUNE); + } } -void tune_negative() -{ - led_negative(); - ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE); -} - -void led_negative() +/** + * Blink red LED and play negative tune (if use_busser == true). + */ +void tune_negative(bool use_buzzer) { blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME; rgbled_set_color(RGBLED_COLOR_RED); rgbled_set_mode(RGBLED_MODE_BLINK_FAST); -} - -int tune_arm() -{ - return ioctl(buzzer, TONE_SET_ALARM, TONE_ARMING_WARNING_TUNE); -} - -int tune_low_bat() -{ - return ioctl(buzzer, TONE_SET_ALARM, TONE_BATTERY_WARNING_SLOW_TUNE); -} - -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); + if (use_buzzer) { + set_tune(TONE_NOTIFY_NEGATIVE_TUNE); + } } int blink_msg_state() diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h index af25a5e979..e75f2592f5 100644 --- a/src/modules/commander/commander_helper.h +++ b/src/modules/commander/commander_helper.h @@ -54,16 +54,10 @@ bool is_rotary_wing(const struct vehicle_status_s *current_status); int buzzer_init(void); void buzzer_deinit(void); -void tune_error(void); -void tune_positive(void); -void tune_neutral(void); -void tune_negative(void); -int tune_arm(void); -int tune_low_bat(void); -int tune_critical_bat(void); -void tune_stop(void); - -void led_negative(); +void set_tune(int tune); +void tune_positive(bool use_buzzer); +void tune_neutral(bool use_buzzer); +void tune_negative(bool use_buzzer); int blink_msg_state(); From 0613b299c033c21e1ddcbd8faeb9d3430d72386c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 11 Feb 2014 09:13:51 +0100 Subject: [PATCH 05/76] commander: play warning tune (as for low battery) when in failsafe state --- src/modules/commander/commander.cpp | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 193a7473eb..20bfca4774 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1311,14 +1311,14 @@ int commander_thread_main(int argc, char *argv[]) /* play tune when armed */ set_tune(TONE_ARMING_WARNING_TUNE); - } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW) { - /* play tune on battery warning */ - set_tune(TONE_BATTERY_WARNING_SLOW_TUNE); - } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) { /* play tune on battery critical */ set_tune(TONE_BATTERY_WARNING_FAST_TUNE); + } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW || status.failsafe_state != FAILSAFE_STATE_NORMAL) { + /* play tune on battery warning or failsafe */ + set_tune(TONE_BATTERY_WARNING_SLOW_TUNE); + } else if (battery_tune_played) { set_tune(TONE_STOP_TUNE); battery_tune_played = false; @@ -1420,11 +1420,8 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a 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); - } - + if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status->failsafe_state != FAILSAFE_STATE_NORMAL) { + rgbled_set_color(RGBLED_COLOR_AMBER); /* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */ } else { From 0ead560059fff0a31183f40a6b848e82aa2dae80 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 11 Feb 2014 18:24:20 +0100 Subject: [PATCH 06/76] commander: tunes cleanup and fixes --- src/modules/commander/commander.cpp | 9 ++---- src/modules/commander/commander_helper.cpp | 32 ++++++++++------------ 2 files changed, 18 insertions(+), 23 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 20bfca4774..7284b38c91 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -607,7 +607,6 @@ int commander_thread_main(int argc, char *argv[]) /* not yet initialized */ commander_initialized = false; - bool battery_tune_played = false; bool arm_tune_played = false; /* set parameters */ @@ -1020,14 +1019,12 @@ int commander_thread_main(int argc, char *argv[]) mavlink_log_critical(mavlink_fd, "#audio: WARNING: LOW BATTERY"); status.battery_warning = VEHICLE_BATTERY_WARNING_LOW; status_changed = true; - battery_tune_played = false; } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.1f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { /* critical battery voltage, this is rather an emergency, change state machine */ critical_battery_voltage_actions_done = true; mavlink_log_critical(mavlink_fd, "#audio: EMERGENCY: CRITICAL BATTERY"); status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL; - battery_tune_played = false; if (armed.armed) { arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed); @@ -1310,6 +1307,7 @@ int commander_thread_main(int argc, char *argv[]) if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available && safety.safety_off))) { /* play tune when armed */ set_tune(TONE_ARMING_WARNING_TUNE); + arm_tune_played = true; } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_CRITICAL) { /* play tune on battery critical */ @@ -1319,13 +1317,12 @@ int commander_thread_main(int argc, char *argv[]) /* play tune on battery warning or failsafe */ set_tune(TONE_BATTERY_WARNING_SLOW_TUNE); - } else if (battery_tune_played) { + } else { set_tune(TONE_STOP_TUNE); - battery_tune_played = false; } /* reset arm_tune_played when disarmed */ - if (status.arming_state != ARMING_STATE_ARMED || (safety.safety_switch_available && !safety.safety_off)) { + if (!armed.armed || (safety.safety_switch_available && !safety.safety_off)) { arm_tune_played = false; } diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index 265c0134cb..fe6c9bfaa5 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -82,20 +82,20 @@ bool is_rotary_wing(const struct vehicle_status_s *current_status) || (current_status->system_type == VEHICLE_TYPE_COAXIAL); } -static int buzzer; +static int buzzer = -1; static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message static hrt_abstime tune_end = 0; // end time of currently played tune, 0 for repeating tunes or silence -static int tune_current = 0; // currently playing tune, can be interrupted after tune_end -static int tune_durations[TONE_NUMBER_OF_TUNES]; +static int tune_current = TONE_STOP_TUNE; // currently playing tune, can be interrupted after tune_end +static unsigned int tune_durations[TONE_NUMBER_OF_TUNES]; int buzzer_init() { tune_end = 0; tune_current = 0; memset(tune_durations, 0, sizeof(tune_durations)); - tune_durations[TONE_NOTIFY_POSITIVE_TUNE] = 700000; - tune_durations[TONE_NOTIFY_NEGATIVE_TUNE] = 700000; - tune_durations[TONE_NOTIFY_NEUTRAL_TUNE] = 700000; + tune_durations[TONE_NOTIFY_POSITIVE_TUNE] = 800000; + tune_durations[TONE_NOTIFY_NEGATIVE_TUNE] = 900000; + tune_durations[TONE_NOTIFY_NEUTRAL_TUNE] = 500000; tune_durations[TONE_ARMING_WARNING_TUNE] = 3000000; buzzer = open(TONEALARM_DEVICE_PATH, O_WRONLY); @@ -105,8 +105,6 @@ int buzzer_init() return ERROR; } - ioctl(buzzer, TONE_SET_ALARM, TONE_STOP_TUNE); - return OK; } @@ -116,15 +114,15 @@ void buzzer_deinit() } void set_tune(int tune) { - int new_tune_duration = tune_durations[tune]; + unsigned int new_tune_duration = tune_durations[tune]; /* don't interrupt currently playing non-repeating tune by repeating */ - if (tune_end == 0 || new_tune_duration > 0 || hrt_absolute_time() > tune_end) { + if (tune_end == 0 || new_tune_duration != 0 || hrt_absolute_time() > tune_end) { /* allow interrupting current non-repeating tune by the same tune */ - if (tune != tune_current || new_tune_duration > 0) { + if (tune != tune_current || new_tune_duration != 0) { ioctl(buzzer, TONE_SET_ALARM, tune); } tune_current = tune; - if (new_tune_duration > 0) { + if (new_tune_duration != 0) { tune_end = hrt_absolute_time() + new_tune_duration; } else { tune_end = 0; @@ -133,7 +131,7 @@ void set_tune(int tune) { } /** - * Blink green LED and play positive tune (if use_busser == true). + * Blink green LED and play positive tune (if use_buzzer == true). */ void tune_positive(bool use_buzzer) { @@ -146,7 +144,7 @@ void tune_positive(bool use_buzzer) } /** - * Blink white LED and play neutral tune (if use_busser == true). + * Blink white LED and play neutral tune (if use_buzzer == true). */ void tune_neutral(bool use_buzzer) { @@ -159,7 +157,7 @@ void tune_neutral(bool use_buzzer) } /** - * Blink red LED and play negative tune (if use_busser == true). + * Blink red LED and play negative tune (if use_buzzer == true). */ void tune_negative(bool use_buzzer) { @@ -185,8 +183,8 @@ int blink_msg_state() } } -static int leds; -static int rgbleds; +static int leds = -1; +static int rgbleds = -1; int led_init() { From 36bd7a797b6116b2f4b1c3fe358ee56eb7982b1d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 12 Feb 2014 11:46:26 +0100 Subject: [PATCH 07/76] navigator: use bearing to home for RTL --- src/modules/navigator/navigator_main.cpp | 30 +++++++++++++++++++----- 1 file changed, 24 insertions(+), 6 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 5139ae6cd2..d7f6fd16ab 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1343,7 +1343,14 @@ Navigator::set_rtl_item() _mission_item.lat = _home_pos.lat; _mission_item.lon = _home_pos.lon; // don't change altitude - _mission_item.yaw = NAN; // TODO set heading to home + if (_pos_sp_triplet.previous.valid) { + /* if previous setpoint is valid then use it to calculate heading to home */ + _mission_item.yaw = get_bearing_to_next_waypoint(_pos_sp_triplet.previous.lat, _pos_sp_triplet.previous.lon, _mission_item.lat, _mission_item.lon); + + } else { + /* else use current position */ + _mission_item.yaw = get_bearing_to_next_waypoint(_global_pos.lat, _global_pos.lon, _mission_item.lat, _mission_item.lon); + } _mission_item.loiter_radius = _parameters.loiter_radius; _mission_item.loiter_direction = 1; _mission_item.nav_cmd = NAV_CMD_WAYPOINT; @@ -1409,17 +1416,28 @@ Navigator::position_setpoint_from_mission_item(position_setpoint_s *sp, mission_ sp->lon = _home_pos.lon; sp->alt = _home_pos.alt + _parameters.rtl_alt; + if (_pos_sp_triplet.previous.valid) { + /* if previous setpoint is valid then use it to calculate heading to home */ + sp->yaw = get_bearing_to_next_waypoint(_pos_sp_triplet.previous.lat, _pos_sp_triplet.previous.lon, sp->lat, sp->lon); + + } else { + /* else use current position */ + sp->yaw = get_bearing_to_next_waypoint(_global_pos.lat, _global_pos.lon, sp->lat, sp->lon); + } + sp->loiter_radius = _parameters.loiter_radius; + sp->loiter_direction = 1; + sp->pitch_min = 0.0f; + } else { sp->lat = item->lat; sp->lon = item->lon; sp->alt = item->altitude_is_relative ? item->altitude + _home_pos.alt : item->altitude; + sp->yaw = item->yaw; + sp->loiter_radius = item->loiter_radius; + sp->loiter_direction = item->loiter_direction; + sp->pitch_min = item->pitch_min; } - sp->yaw = item->yaw; - sp->loiter_radius = item->loiter_radius; - sp->loiter_direction = item->loiter_direction; - sp->pitch_min = item->pitch_min; - if (item->nav_cmd == NAV_CMD_TAKEOFF) { sp->type = SETPOINT_TYPE_TAKEOFF; From 4a66e285adcd88cf42c3907753abd9b433815e45 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 13 Feb 2014 00:05:27 +0100 Subject: [PATCH 08/76] navigator mavlink log info messages: add #audio tag --- src/modules/navigator/navigator_main.cpp | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 5139ae6cd2..2711be24fc 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -865,7 +865,7 @@ Navigator::task_main() /* notify user about state changes */ if (myState != prevState) { - mavlink_log_info(_mavlink_fd, "[navigator] nav state: %s", nav_states_str[myState]); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] nav state: %s", nav_states_str[myState]); prevState = myState; /* reset time counter on state changes */ @@ -1073,11 +1073,11 @@ Navigator::start_loiter() /* use current altitude if above min altitude set by parameter */ if (_global_pos.alt < min_alt_amsl) { _pos_sp_triplet.current.alt = min_alt_amsl; - mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt)); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt)); } else { _pos_sp_triplet.current.alt = _global_pos.alt; - mavlink_log_info(_mavlink_fd, "[navigator] loiter at current altitude"); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] loiter at current altitude"); } _pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER; @@ -1175,14 +1175,14 @@ Navigator::set_mission_item() } if (_do_takeoff) { - mavlink_log_info(_mavlink_fd, "[navigator] takeoff to %.1fm above home", _pos_sp_triplet.current.alt - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] takeoff to %.1fm above home", _pos_sp_triplet.current.alt - _home_pos.alt); } else { if (onboard) { - mavlink_log_info(_mavlink_fd, "[navigator] heading to onboard WP %d", index); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] heading to onboard WP %d", index); } else { - mavlink_log_info(_mavlink_fd, "[navigator] heading to offboard WP %d", index); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] heading to offboard WP %d", index); } } @@ -1331,7 +1331,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm above home", climb_alt - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] RTL: climb to %.1fm above home", climb_alt - _home_pos.alt); break; } @@ -1357,7 +1357,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: return at %.1fm above home", _mission_item.altitude - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] RTL: return at %.1fm above home", _mission_item.altitude - _home_pos.alt); break; } @@ -1384,12 +1384,12 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm above home", _mission_item.altitude - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] RTL: descend to %.1fm above home", _mission_item.altitude - _home_pos.alt); break; } default: { - mavlink_log_critical(_mavlink_fd, "[navigator] error: unknown RTL state: %d", _rtl_state); + mavlink_log_critical(_mavlink_fd, "#audio: [navigator] error: unknown RTL state: %d", _rtl_state); start_loiter(); break; } @@ -1516,7 +1516,7 @@ Navigator::check_mission_item_reached() _time_first_inside_orbit = now; if (_mission_item.time_inside > 0.01f) { - mavlink_log_info(_mavlink_fd, "[navigator] waypoint reached, wait for %.1fs", _mission_item.time_inside); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] waypoint reached, wait for %.1fs", _mission_item.time_inside); } } @@ -1541,7 +1541,7 @@ Navigator::on_mission_item_reached() if (_do_takeoff) { /* takeoff completed */ _do_takeoff = false; - mavlink_log_info(_mavlink_fd, "[navigator] takeoff completed"); + mavlink_log_info(_mavlink_fd, "#audio: [navigator] takeoff completed"); } else { /* advance by one mission item */ From 8bc0287eccc7871db17c199a3b330e74c92c068a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 22:45:54 +0400 Subject: [PATCH 09/76] commander: disarm system when safety enabled --- src/modules/commander/commander.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 6d14472f36..29a930ebb3 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -902,11 +902,13 @@ int commander_thread_main(int argc, char *argv[]) if (updated) { orb_copy(ORB_ID(safety), safety_sub, &safety); - // XXX this would be the right approach to do it, but do we *WANT* this? - // /* disarm if safety is now on and still armed */ - // if (safety.safety_switch_available && !safety.safety_off) { - // (void)arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed); - // } + /* disarm if safety is now on and still armed */ + if (safety.safety_switch_available && !safety.safety_off && armed.armed) { + arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); + if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed)) { + mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch"); + } + } } /* update global position estimate */ From 71d4c7fed8bc809fc38ba54147156fc834d38846 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 5 Feb 2014 19:03:26 +0100 Subject: [PATCH 10/76] Startup: Hex vs Hexa --- ROMFS/px4fmu_common/init.d/rcS | 2 +- ROMFS/px4fmu_common/mixers/{FMU_hex_+.mix => FMU_hexa_+.mix} | 0 ROMFS/px4fmu_common/mixers/{FMU_hex_x.mix => FMU_hexa_x.mix} | 0 3 files changed, 1 insertion(+), 1 deletion(-) rename ROMFS/px4fmu_common/mixers/{FMU_hex_+.mix => FMU_hexa_+.mix} (100%) rename ROMFS/px4fmu_common/mixers/{FMU_hex_x.mix => FMU_hexa_x.mix} (100%) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 50ac9759a5..d127853683 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -465,7 +465,7 @@ then set MAV_TYPE 2 # Use mixer to detect vehicle type - if [ $MIXER == FMU_hex_x -o $MIXER == FMU_hex_+ ] + if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ] then set MAV_TYPE 13 fi diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix similarity index 100% rename from ROMFS/px4fmu_common/mixers/FMU_hex_+.mix rename to ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix similarity index 100% rename from ROMFS/px4fmu_common/mixers/FMU_hex_x.mix rename to ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix From e407766cc7c9f2c2d06deb064b9a1c89cb17a203 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:56:31 +0400 Subject: [PATCH 11/76] mc_att_control: minor cleanup and refactoring, move some class attributes to local variables --- .../mc_att_control/mc_att_control_main.cpp | 43 +++++++++---------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 38fde0cace..76ee2c311c 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -71,7 +71,6 @@ #include #include #include -#include #include #include #include @@ -84,8 +83,8 @@ */ extern "C" __EXPORT int mc_att_control_main(int argc, char *argv[]); -#define MIN_TAKEOFF_THROTTLE 0.3f #define YAW_DEADZONE 0.05f +#define MIN_TAKEOFF_THRUST 0.2f #define RATES_I_LIMIT 0.3f class MulticopterAttitudeControl @@ -135,15 +134,13 @@ private: perf_counter_t _loop_perf; /**< loop performance counter */ - math::Matrix<3, 3> _R_sp; /**< attitude setpoint rotation matrix */ - math::Matrix<3, 3> _R; /**< rotation matrix for current state */ math::Vector<3> _rates_prev; /**< angular rates on previous step */ math::Vector<3> _rates_sp; /**< angular rates setpoint */ math::Vector<3> _rates_int; /**< angular rates integral error */ float _thrust_sp; /**< thrust setpoint */ math::Vector<3> _att_control; /**< attitude control vector */ - math::Matrix<3, 3> I; /**< identity matrix */ + math::Matrix<3, 3> _I; /**< identity matrix */ bool _reset_yaw_sp; /**< reset yaw setpoint flag */ @@ -262,7 +259,7 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() : _actuators_0_pub(-1), /* performance counters */ - _loop_perf(perf_alloc(PC_ELAPSED, "mc att control")) + _loop_perf(perf_alloc(PC_ELAPSED, "mc_att_control")) { memset(&_v_att, 0, sizeof(_v_att)); @@ -276,15 +273,13 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() : _params.rate_i.zero(); _params.rate_d.zero(); - _R_sp.identity(); - _R.identity(); _rates_prev.zero(); _rates_sp.zero(); _rates_int.zero(); _thrust_sp = 0.0f; _att_control.zero(); - I.identity(); + _I.identity(); _params_handles.roll_p = param_find("MC_ROLL_P"); _params_handles.roll_rate_p = param_find("MC_ROLLRATE_P"); @@ -535,16 +530,17 @@ MulticopterAttitudeControl::control_attitude(float dt) _thrust_sp = _v_att_sp.thrust; /* construct attitude setpoint rotation matrix */ + math::Matrix<3, 3> R_sp; if (_v_att_sp.R_valid) { /* rotation matrix in _att_sp is valid, use it */ - _R_sp.set(&_v_att_sp.R_body[0][0]); + R_sp.set(&_v_att_sp.R_body[0][0]); } else { /* rotation matrix in _att_sp is not valid, use euler angles instead */ - _R_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body); + R_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body); /* copy rotation matrix back to setpoint struct */ - memcpy(&_v_att_sp.R_body[0][0], &_R_sp.data[0][0], sizeof(_v_att_sp.R_body)); + memcpy(&_v_att_sp.R_body[0][0], &R_sp.data[0][0], sizeof(_v_att_sp.R_body)); _v_att_sp.R_valid = true; } @@ -561,23 +557,24 @@ MulticopterAttitudeControl::control_attitude(float dt) } /* rotation matrix for current state */ - _R.set(_v_att.R); + math::Matrix<3, 3> R; + R.set(_v_att.R); /* all input data is ready, run controller itself */ /* try to move thrust vector shortest way, because yaw response is slower than roll/pitch */ - math::Vector<3> R_z(_R(0, 2), _R(1, 2), _R(2, 2)); - math::Vector<3> R_sp_z(_R_sp(0, 2), _R_sp(1, 2), _R_sp(2, 2)); + math::Vector<3> R_z(R(0, 2), R(1, 2), R(2, 2)); + math::Vector<3> R_sp_z(R_sp(0, 2), R_sp(1, 2), R_sp(2, 2)); /* axis and sin(angle) of desired rotation */ - math::Vector<3> e_R = _R.transposed() * (R_z % R_sp_z); + math::Vector<3> e_R = R.transposed() * (R_z % R_sp_z); /* calculate angle error */ float e_R_z_sin = e_R.length(); float e_R_z_cos = R_z * R_sp_z; /* calculate weight for yaw control */ - float yaw_w = _R_sp(2, 2) * _R_sp(2, 2); + float yaw_w = R_sp(2, 2) * R_sp(2, 2); /* calculate rotation matrix after roll/pitch only rotation */ math::Matrix<3, 3> R_rp; @@ -600,15 +597,15 @@ MulticopterAttitudeControl::control_attitude(float dt) e_R_cp(2, 1) = e_R_z_axis(0); /* rotation matrix for roll/pitch only rotation */ - R_rp = _R * (I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); + R_rp = R * (_I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); } else { /* zero roll/pitch rotation */ - R_rp = _R; + R_rp = R; } - /* R_rp and _R_sp has the same Z axis, calculate yaw error */ - math::Vector<3> R_sp_x(_R_sp(0, 0), _R_sp(1, 0), _R_sp(2, 0)); + /* R_rp and R_sp has the same Z axis, calculate yaw error */ + math::Vector<3> R_sp_x(R_sp(0, 0), R_sp(1, 0), R_sp(2, 0)); math::Vector<3> R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0)); e_R(2) = atan2f((R_rp_x % R_sp_x) * R_sp_z, R_rp_x * R_sp_x) * yaw_w; @@ -616,7 +613,7 @@ MulticopterAttitudeControl::control_attitude(float dt) /* for large thrust vector rotations use another rotation method: * calculate angle and axis for R -> R_sp rotation directly */ math::Quaternion q; - q.from_dcm(_R.transposed() * _R_sp); + q.from_dcm(R.transposed() * R_sp); math::Vector<3> e_R_d = q.imag(); e_R_d.normalize(); e_R_d *= 2.0f * atan2f(e_R_d.length(), q(0)); @@ -658,7 +655,7 @@ MulticopterAttitudeControl::control_attitude_rates(float dt) _rates_prev = rates; /* update integral only if not saturated on low limit */ - if (_thrust_sp > 0.2f) { + if (_thrust_sp > MIN_TAKEOFF_THRUST) { for (int i = 0; i < 3; i++) { if (fabsf(_att_control(i)) < _thrust_sp) { float rate_i = _rates_int(i) + _params.rate_i(i) * rates_err(i) * dt; From 55f5f1815f6a8f2efb969cea2eb061bdc2d9b92a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:57:23 +0400 Subject: [PATCH 12/76] mc_att_control: remove rate limiting to run at 250Hz --- src/modules/mc_att_control/mc_att_control_main.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 76ee2c311c..e92b7f3758 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -692,9 +692,6 @@ MulticopterAttitudeControl::task_main() _manual_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); - /* rate limit attitude updates to 200Hz, failsafe against spam, normally runs at the same rate as attitude estimator */ - orb_set_interval(_v_att_sub, 5); - /* initialize parameters cache */ parameters_update(); From 2b4af6635708be2248abf53edb65a9223fedcd6a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:58:13 +0400 Subject: [PATCH 13/76] mc_att_control: poll vehicle_rates_setpoint if attitude controller disabled --- src/modules/mc_att_control/mc_att_control_main.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index e92b7f3758..b5df83d859 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -761,10 +761,12 @@ MulticopterAttitudeControl::task_main() } } else { - /* attitude controller disabled */ - // TODO poll 'attitude_rates_setpoint' topic - _rates_sp.zero(); - _thrust_sp = 0.0f; + /* attitude controller disabled, poll rates setpoint topic */ + vehicle_rates_setpoint_poll(); + _rates_sp(0) = _v_rates_sp.roll; + _rates_sp(1) = _v_rates_sp.pitch; + _rates_sp(2) = _v_rates_sp.yaw; + _thrust_sp = _v_rates_sp.thrust; } if (_v_control_mode.flag_control_rates_enabled) { From 969f564a132e7b14e94028798ca5a4d6c5f13244 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:58:58 +0400 Subject: [PATCH 14/76] mc_att_control: code style fixed --- src/modules/mc_att_control/mc_att_control_main.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index b5df83d859..01902ed0cf 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -531,6 +531,7 @@ MulticopterAttitudeControl::control_attitude(float dt) /* construct attitude setpoint rotation matrix */ math::Matrix<3, 3> R_sp; + if (_v_att_sp.R_valid) { /* rotation matrix in _att_sp is valid, use it */ R_sp.set(&_v_att_sp.R_body[0][0]); @@ -762,10 +763,10 @@ MulticopterAttitudeControl::task_main() } else { /* attitude controller disabled, poll rates setpoint topic */ - vehicle_rates_setpoint_poll(); - _rates_sp(0) = _v_rates_sp.roll; - _rates_sp(1) = _v_rates_sp.pitch; - _rates_sp(2) = _v_rates_sp.yaw; + vehicle_rates_setpoint_poll(); + _rates_sp(0) = _v_rates_sp.roll; + _rates_sp(1) = _v_rates_sp.pitch; + _rates_sp(2) = _v_rates_sp.yaw; _thrust_sp = _v_rates_sp.thrust; } From 3eca9f9b6b866e1c7ad8b57d16ad16cb073d6085 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:11:03 +0100 Subject: [PATCH 15/76] Updated logging/conv.zip with latest script versions from Tools directory. --- ROMFS/px4fmu_common/logging/conv.zip | Bin 10087 -> 9922 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ROMFS/px4fmu_common/logging/conv.zip b/ROMFS/px4fmu_common/logging/conv.zip index 7cb837e5666f51eca7ed803dfef4581f01bec1f3..7f485184c6d453a422f795489fe64684e9b179e3 100644 GIT binary patch delta 9806 zcmZ{KQ*fYN*K9JeZQHgrv6G22v27<$Y;)pF>||owp4hf+ocFE2>U`f{bHQiclD7%pS+-wEEqUC$TtvZ5He2V`qL1Zit5OXsS5Eu{;5F2}QV|zO{M%xPk zYx^~+#4V^_Uo-VkAx5I3Udsxkl1W$yWPp!UJ{nIL*wim6^!E0)@_&j@ULis*HC2)E zzGu;Xbosi{RTzGQq?r=N*ID9Qnr21g83egz#{Qy{%T>bir4gvDdmBN9pySc<;~5i$ z)64MA${@xcd~A+6FoMf7l$OQ|NYLn6g7=cOxUC7Thb4Uj-H49$IU>njpXZ%J;MRv5 z$6fMcTpDhq9-kG7fUH&*>h0WK5Hv;MjM0uUKqj{?AyJ~OsmyzzgROJez>+6QA7HTo z6S{7)Tk|-1rEFhkvZ7$Ul&AdY4ZHE%Q5m5`3vVQ(SC$~$m?8Tt0L*a%&eZG^wo+{q zi%tSewht&CZO|Z0O4KWikq*d{xDhD<#dbH*XMIc3-o7R8~*C;PklB#(@5c#nRIh7BcK6)^!%MqkXoIkTLe8Bbrj`HdF!pmQdHTP z1@ijHpJc~1om`E4N)thu`yDi_@w`^zN`J$DD_ttU@mJr-sVfuGja>`C%7|V7df1V_ z6Aijn?}@(Da(djE{dsidvshA;vTW1-xhFTb&^T`u6ylH#aR%CL&;RjhcJYb{`z3#@ z35v(ghV{2L9P7fX#t9w_wAj?6T2p|RSZ~Z%77%LE$;+~6c>hr7r8I~HV9!+5aWbiL zE{Xd~v0)v}Q1M6W4<_jQ!GlYI@007-i=5+szRAC0b!M`RZGf+;sraTFok)|vatUkV zF^#!4#-mPbAS->Fh-YKwMm@(y4gc-mC_hji-}XBUx|w1OV3xbGGf57CIFI3cO#G^I{?Q~7^1(Y4NNvr^%TiRa6n9MNW495(D)2)DjG(coeYbKc1v`S4}ngD4Te30!ML2rYXB)8 zw-ckHWxN$WE$R{cDFSUe`;P*{K()?QZQvc`!TB}n+C8nzH0+E}Gp7eV`67)ST*50zm6e|iEBn)*nJOk6I25txKgmw4uMlyc zB|;prys8xHsbJy3Ltq*i-Yk_21p~FR7o7ZrxzN`|ltep>&2gh7P;u+A3xtHuRo-Aj z0jUIIYznH?3HE%vCW_>E+7ZCINA!WcJgB@>W;@Dh|3=j*V>KBhQMFmAB6YikEGz}q zg0#~QS+Ds`>26C5fU}#fd|59X%AQUQ=r4Jy_?o`Vow}q}8uemWo~XR|{MEl5$w?ejQ@4w=WX zLO1Pg&82tLMXUgKwT458RSlj4i74jzaC<~c=vH=mQ)3_SH{)2+H?P%nm8~O2A=^R( z_zVq|n(-GZ4+W@jcW#GZ0?;kco|a2EsABPwC!xlX#!%p6sGo~UY0p9cL3l`jm081d zw?<%@{K(W4L4-QoUkL0Km#f~PvAUXQG*{*`SITs%8|;z8SRc`k2DeC)Y&M$35|>Oj zYDPU`ECGNNQh~-Y=z_8S8&VB|;Iaxm&i0_SuH#?W03(FM3t8`3R}lJcuA^}-@hqDr z{>?d)7R89DSyfwf>W?l`me;`cw2e*8__MMHG$VKu5m747dzx##Q`Skd%)=d0taWS8 zv$#0Cw{)zvO7}Bt|I{tJ_C1>fD?LwoNY2!RnkBGEJ1K?Jamvj6ff?8LBZTQZ5(t_z zrgyE;ttnfQ&Z(1DQZ7Xw|4rdx^*NiRma?x&i`-;yWJ;cEe(MsIvDD;VH4>Jy)M*{(HWIB1*2J9l%nTkHhFX+@J%#;YfCE zv$?QnFS5A$5UP}rZm+`@KjT(_xxs3_{kM55d`ot*Xk(;&!6~MGek}|cK4rOaea3>z z0NL7N1Yy$cjsoiK^qKct7ipbe5l<5 z%JxI0&+{GJCzzg#YkOfm04uFMv7rqk#~DN2M6R()ye-iZ<2y@CW#qcLg(IJ?9=5am zO^~FFj)5Tf%h`mQ_A-{R8-CAbM?8=kseNm3s^5&Bo(#^%aZqrkwPj$paoLk|S!uyE z$axe%Ub${}E}G^V6veC;oLsCFMHXKY?6Ay2v0%l~LElwKEHz8%;_YI45M(-*2x^?6sj%X>aVphRxBZ`1afoN&J2iP2RVVl zoi40`DoDgW54uj6Tcx@?;_y+lt|qtQYIzRn!LmxqaVqs|mKS60xNmRw^-tI=HU8Ay zc`FiM`101uQ9;RZkhg^DZWrTQl)f+^9fH{`rUL22rHlBXvy$6&PP|?Ann-#9lMy6+ zSNK@VCmIwiAw3R5Cce}sLk^I8Ky8FjaEm*zXdNbf#nS^wH;-_v(>3E)$H_;- zswqzED!n9^Kr>~QaMOq%#zAzM+lNivwx^_QY-bu&^5Q1w{z*EmeN}x;$mAzqM68l- z_4Xs`@i}#%n+7H-(eL?%RQZ{|PR%E(3B~z6e}KE zl8qiT+MX8fuMsh6j8VAIz3Y1$RJ8lH4lHAY$)R$Sb};FHkcFS1v{fUjGO%if&2rHu zrmWyuwgxHT;}sa}$3`XXwaC#NNXl{;L7F5V&VU2&yWAeK9w4;kW7 zKR+CslaWejJD%cRZd-=$0BFzkcKdOF^P4FEZ%4nO?L|gg98HfS);RcSReVA5`>$f55**inY?@=DYywqDwA4ghSgQtlz0>N8CwzHUzrnHg5J>SN+qfyQR zQG*pEjf07FE^KG#YA933`3j0yud?#juHr;2CMhl6CF%v<6R+8qUGH!S)w*-V^h?v% ztE_=*LTkPQ6R64y2cP48N`=^o3NieZCXXu}g$ zE4TM-6~~y0J1=VNoAqTcas2QxIS&(K37j!S2(?|UGg!dBD_Odoex&Q0jzTkaeFie1 zDvTO95Mm5@39I=1&E!=C$yW#ya!t2~b?k#B=mz?$i^kK03odDcC7RSkteI)B4TGvZ zLdF0a`HwfsMg`bcH&?>Oy7Z%=VVw}ammNympRKgOk4RO&a5or<=g{`h4cF6?`kt-M%}|V z@$d^&w?q=Q++lZaI1F-Zlkxg!YUtnUsTXh&Ixi($ZlE$*^CR^4f8F@LR4Z?h#OaET zIM*EgmBzq@w4{YL={3I3I^;c>?XNx}4i4I-sT=(Tu5h>II>}la2o7Q&lPX@>|>KSrS!l1aQ$Khb9mQ z7nmXm$}UKC^DOnw6kP3^`E~jDfKKcGbPXaDdZ@(Iq_No?2KK5RK|(YCg?FJ zK7QKufXbPhW5 zSedhtbso$nfy$ca+Zb{#-|De^7;ik5W>6ssWctQS8P+YT;rOK{u&a5l|DAbUU(N3w zqlWgqTxFUY`}Wn4GRj6bi3lGDXvE_eV9b_|6<-Tfdk&K3%*_Z7TV$mk_ev;dmM+TM z(cd9cWy|73w1$c)AWM8LuID$-sP^W-eSk!Z|F|r5=Ili`y(&p@;uNYHNOQCc@W54p zLCzG#@+Xz05WCGKd3Uzr&V6eANF5AXZCO7s;lG&p{kl1R7YR>iqZwSD zw^Q{{rMt@s7nJ|#gZCG^CW-V8w2YCLYoEdTbm>h(>1l?toa%UwD95B-qs8@Hhddcq zCH7r|Jh4YlOr&USjWEdo60gN6jp!!nJ?oG%wERqo*z3{d1SiArT)~o1lyU#*@H^Kb z<$F4r68*S)mla%*#7oNvJ7gz>D&HgS7QZ!^6U4Mh(xZ#G<2pNi7pmr%t zAgedVUfgG;Knz&;5w4xQ!p^)3of#Im1&41`5tCc>}7ebEqfB2^!1T)Iu#Aix5$#69bcl|xDI11-+C_5C(iJ4OSz zQ-A{{(vXRlcMsI$SG_#;$8SZgSkz(O0Zt8A)WhBZw_eQyhdtv7%gry88sDSX(M=aI zNhjW8NHD@xJ4Q^b?P+opF14L%lbw}V5PxxhmVse<`yC@>n?(oKVDjQnKikM`Tp6O70R|O+F6cqfA*X6NsNNt+EOA+0DrB9r?6IEd@ z2pDk!4c!H8pZBv*XtL+i%p!Hqi8Qrafs9#Te1dx-3J}wX3Dh0a({D2v7`>M7fp|8~ z6W-c6c8a;^&ItndQ+K`9#tEPtMGr46fz?2lHJ6Cp!~(C!x{Aecl0;SUDrTXyDY;6Y zyQVS-@!T1Q13XWU-jOJ$f4{jLnumq!1IG8p6&zCMuv?r68t)Pm#jG8gVeorQ;W-s| z+;l!ot3eK;ySuK~vtR7E18gD=$}xWTW^hTE2q%_ye$MdZ{)O|2#nQ{k!5%XM%IQEE z={Pd?A(*dzz%eKt2229Cb+F_Q^J4pk-dbE@2-x++cj;6VvHH{T6uI&4Ia})?g@n|D zz3N*&h-X>E3F3u=;N)f7z*$0~%t7%<9^oh=MOk_a#W7TiEzdm4s;$73(R0_`)*6rT z9j^H#bH9woL@K?P6Fq)fq&q6aaaEvq$Ns?Thndr(Q_YBtOo&}FRk?GI83%)S{to$~ zu3PMg_RG6SH+8*?HDm;;JE~MBLGR(2$nz7&U#FdIvhMtrIIj$kNpOOAkQ@&af00+A z+}X}!Bt~9f`;A_z+1c;YyX0*t*PT`92q*2<$>R-avIC5>pYYE9a>@OpcL8{Q_id2h z3{MlZ^VmO3V$7Y(1AETIBvtk! z8qaB_^pr$3g`Wwo3%>SN_9y;&r=pP!??ih*;b8F1gn*uLTq&?d2NQF@PCjMmDs=tB zEa3B0PFDL8<70GX)j8}gZU6{@X=6Rd#^RGq;FJC?yjzkon+{0E{R`&8LiAllz!1Yk z9ojpcecqcSBj{6JcgEemuPNdaBDV{B|v_^hjoTKjH<}WQZ!*%%<_{T z*;7l$JNA>uPsT$+S60|RaR|QO-dYZ&N9>LC?atI6DfF0r6#q;QmGJ>qVtWo3Ql>)@ zYf)q9LDVOEw)!U*W_lw!lN!bfN)%3{i#wnuR2QXX)xLk&rb_cO(`Zp+x}bjIyN4jG zzZ&pCrQE8%Pb&T$ueUp+71(Pnfw~`!6Zk!C-MSpql@i*?GmPYN9g}E}bU0y>!WEc9 z@Vlnr7LMB|%GO5x&Sywc3fzsKwGAN{Ihr6&RhF1L#yk~_7qNFypbO(Z)(HZAaqg;u zKZxXA;+0VC5!K{ULg?b6f}8XucC->rFHk}|b1+zp-=sfDn3NjOZO=|n9_5BzYyX*A z^pl8a6WIXGiv+Z24C#*zcfn3L zjmee$098Wo78vE%%=PI>X=F7?D9pnCK1)k7xgzt;NQGR7@QE5A; z1wLMPKovGi^`uhv+XU%2o_)H-`ET)4qg7i>6C3)RvdI0S4jZ%p)j~Wn+KreGoIhy` zP~7-2zTg3f4vAgU3}J2mh>z>M8{ee%ntM=WCu01y#EEhSy%jxv-gHpe@6S1JDw3ve zAMN?`5%2|l$oo3NeqEdb^P{>E()qpj1@#|$+VHogSX7XLAOH^n^3DnZg7}X;?QHUo zLCvaf;%e)_=-}C@^JTx*g!jMl5M%q>+ystBcaXjkjDLb5ChCPCRUTGKFm#WM_Sf#-#+I?a1q8GIrHH95!pb$C@CdU zh)f92+cuJ0s+p-t8>uI=YsRw!q8P)8XMaI`?{h*=LJxy8Lk~SOu#DwT^HWdR+jxj$ zqe#rzVave>um*1MvtwX5vx0(}KpREdWRf5dAt?*aD%TU`<9{^NO7FY;G^-)7;`Mtj zFQQ*bXu`;Tu(ni1E)4(TSq7EU0inD1N0i)yIYP73NcO}?C8TMB zu#dT3@(>q-p}gH=;dys?en%FpK`d#s@*LEhNKIR>$qAZ2>&WM@6d~I+7tx!Ut3cKD z;(;}Uc3+*MDcOF8hdLw&;?5z&v4_1cTSgLF@GmA2pVl+QYN_O5SGjg8K*GNqMlPik z3B#n7(DzTz5o{7&zKR@s#J}!^nq&MIdw!eJ*oZLP)0q0Llsp*GD zvOqUJ7Hz7IhqteWs+!HtZtm7cCPf8+ryDcB>#a+yyUp)w=N=bWx;hxg8vNTl*vtf5 za^d>XJ?{KBCGL8|P#$f4=}H?EXf$)Q%cjBUZI;|Dj&92l^%|9CvMt1*sGmhhUCuCXl)Pa?&Oa76vpE9yONX+Vj0w^dHm; z#G9gble(N~HyNY|xQ@^(69t_}fAzL#=4brjO)8iO2rj{YoF{TA?Ssg~Zy|*|ha6JQq^Kk3a|u2=;wbuaYYc_^{76k? zSmaS=a?vdP$qezsq|`yN(Uspp!@j?r`&W?+n$sBIM5+W&Aab?o{GwdQps8Q$eV2W1 zlf{)n-XsIepb+x5c&QD&bwAh-4_zvEm90%-lzcP;sMW`U_PkqTd}N5Oks6?$AyWc}ewhPEFY`6Kc2%*y>D=AhbW(OSAYuMl zLUt5xK&IV`6E8%~*jJ2dVT=B8Rjx8({Vh#A4|hIe3mW?e-XfvbRDWheA?BUUBYRN( zrU5*tM3KE=9NdZgL~9znZ^Q!?EH0-?Es7u!$P~KY`#1^_W7>d zh!_WN3iy$UPZ zTZL9c`VI^dlA$%Ndvf8LXaVG6U-?35=!}bBvtE@sYcGQOs6iLhKZz`4Za$>A37D^OEk1h&1%Hc8BFRO;r~*A$ZQgu(%D382g|w3u$FUdx8Q zR79MHTy!_m-%3@}k|=69Wm!YqIVcHe7i_*Pum74sTq=WxS{$p>kT(|@BzDaqi6zjg zq}O}dj&Lx_thK}dA}S%Jth>n!-qI%A}Zh%oQ)c8_+^ve zGJ+-$G{au+`G-~N&>iMhp-qojbzvh1AqyyA;#0~7M-NN!V=Y#g912It8ra7(JH2_k zvHk+}gTl9+|1}$5bNOU!+HY-{TV#smxq~k6Lv0QV?S|_V|)|CeSgYnriZNVDnJ0zKI)*xtnDL-+h|32p=63~ZGcyRfpy789 zH5f)U28%UvThHqB*&3ltYXIwqxv*V%9)ZoNlDWq^>WBxks(5Ih_3O8R8-nLUn@&uP zQ#Z?7^(?-T(7*e|7yL_8ZuijR;}Io`ay?JiBlJ$gKp_jBtEahi!G%nNLg@%s@>+wSDVxQxDHqtveEdS{U2ZQ#7Em)Gi8tq3#Akz> z>66Xz(I&gB#ezVn)%WXjw-;LmpJm}nX$WIH@Op0q-05MoeJM)Za9V&$6=5C8zxU;O zpQu}C^i z1MMeVe^jf_?|qM0YamB8tJp^DPKBUJ?g1i^Dgy#*m7wFYGHaq@z%?b=%qHQ6VxV>w z(Pm}JwCkcbGXWm?kgqV)VH2q|q#WcrUypplV#5SkQ$@$Lk3{e##O`Gjm(b>E0U|Xc zuawoNH^N@c`Yg19IBeGc$lEg%QL$iS`5?sVnC3aJj9~ru0q_ipRy;eP=r_k-2;T8q z?ih4}5mD1Vk?V{sp2zBAW4RL(wiw=eJgN;l^Az+I?x!3>dUuDvHQBRc$(9E7 z_2q}maOfsOY`MHgp;Lr(>&C4ivLtmn-WFKQ{e2aq@Kr$SMd=TcW?4ZlF>R!o_7Xub zZd->OL=c^FOP_2#vnpcd$D$1#h>n#uS#z?jrt{S_ORB5Q+~=- zH3(4qB|x@6KfzSYB6mgi7w(MV^SwLw*cnef0;A^j&3X%BkK}&eC|WrKw`te~^__br&( zHmhQVoOfrRJ>-sCsiR_tNuCsTE$aN(Nq*q0k+Mh?j?sO&M%NPcUy9FtF1hP-amV<4 zU67i+RVD>-_`h+>*z%1V&h6I6c4-f)A$?4 zA^^E!=MM|0^mAz)WR|}SHp3m|eZ*@MJg|Ic##ofthm5xCk%pnIWJzxcRvm_$4@Zj4 zjZdhzX!D5&p5a$5i!E`#xq6;3Bz=GD;lWP(c*SYDC|c`*Z?`77P1zfP&6#^$f3t|n z36|hlUariyi?++(Q?~_Is^I&jbL^~ADF|pOLcP0&Cm}f0iA+6!9C^jp<8RYL@f3hg zjU+&|_WVAVB%U-|jn{TbA4TDL9BwJpdr5W3r;MG{ali28ljZV@s%{lBceA(}q+#lx zP`FLiaqgZxpIQHAeFdcd%&4%vC~AtWTXp5w%gg5<@rHUFIx2d zh+&_>NG5x0g`a&njhAmm1$qFgd6q%rZa*s(L3uotE&UUQ@Xy}TI3UV-qfq`S-EHgT z6qD^zzdt-373lPQ!vx@$pP z9Ru^nUPD=1Rg&xS*EVhM&lo@HpTDB|t=_}}ZF^M7Mm z{|)=!0@>kz6!O2*|AXWDC)V}9_40p%|6j!X4|bRAziFx@3jz6W5A2_+`1gOxe_#Ix DCnVIZ literal 10087 zcmaL7V{j!v*Zq6qi8b-WwoYu@b~3Ruv27bCwrx&qn-kl{1b3eIR^58)|K5A6t7~_E z=vCEK>&x2vrzisf`5gcNd;_41Ac~;1hZwjZ007J^000u;2f)e1#@?L8z{JJYfx*E; zO%)aZK`{rbEVu%z?BWg&0E2u40|5T#eYduc{RTVwSLf&Vs=&Ob3ipT&^VL98!Sy1Y z`jRQoLtoBNXx?aYwOR?Vo0Bcn=lM9cNHVfu(FC6YGInbJ!=0DlI%Mz9e(ia~%Nx6q zfl3ScYmK(K4KOmwMkJ7^rm`bXNH9?@2Lod)Dp+lHynv?9F6TIVDKiV;rFkIKYz;3Bf5Ch-qX|N?qkU9?pV<-K9z`#ZbF6`CW_Fi+w2FcLJukytO^TKNyog*Lu3Qj0$T}|*x*y#1#v+PKorgM^R zci~g&oh8_tM7z^CS6E7wz_-$h)(;mciFG37LA`wkS-0%~oJ8JYPK(q+;$$+}g^O5* zQbUwNC6r(`ItwsY5&3YpaT?7{tX*5Z8Ucz)2=0?cNd6PRL*XexdQnJf+{VsQX0v{FM`>qGo((^C9 zoQa$tpBp0biCrt#z`waxLtQ%8>Cw9jl=iIRlszR~JIPo`;~ei~`+Uj!kU$U-O)J>5papx6c~e1D-*AboN=+cARG*U2`IK;r z`dBCl>^h2Giz5tO-#;q$%LM2uImOFTF z15Tl2KU2flP8UMuZ0IQMfdE;xIr1Vx0MiW7vI=BEJUgqlMso3ED2~d;fTGyTPYxg; z9-6ci8j)y=qRNm|_k;7W;z9R>sv+M;G|o!!ry4r$uT&H-P`xgZOV7b+xMlJ3UHAt| z@7~zlQ}`x{vTAg);NzH{a`jkJEw8Y^Aqow%jTzZ6eJX`%$d+i6O(s1yy~SbG7)l%1 zU(w688v4u)Egv_do{)S*&dm!u;3+hy7QZUW@i9_CtH83k%?;#8{3Zc&kDCRzBRx1g z8yx@Iln4M4SsiA=;>rui0I&E5fR+6#r$DL_^wrW~&v_!&RXQ>ur zZ*mMrdrSxh;upU$c#_rI5yyqBBu`RsFqv_g8ZWI-DqQ98XN2c)Lp5Zyq1#n*GB$jB zmnCIsWFz9e7G?WsWp=9L6kZ)^m%WNtwFKj4zfVAXsAKLHu*%Dy!S-}J@U*lcw$6+0mql^qO1PMlw9WCzcc5TmM zFB76W{8^t4>+G*F8kc||q0jo!2o_r^p+}&&p&9+Knt1+gLJrI_$tJMo;Kh;$c|?RB69 zO@YF&0_P~_y{kw{t#mtt+WFgEw^QxQpj_{+?oPHH=-8Z6V0iG~kRkI>x3a zL{Mx}cWib{tDX{_YD`_MAgqCDbflvmIW#frWum#j6n0?2MR4AQ_+ZNU$vAfE5S590 zV7-e{p)gTEWpB9}*6+N>G7du#Gqvc>nj3kwn1VtpOdRuIqr0yVf#rTP*8ZkytGX0Z z!=}Art+{j;bJfYDpo4pfYudZd&p6Y1z6v>f=Je*3TK7w1G=j=O9>IdXn5Tlz!GCOY z6{>`>ekR}{AXS^b8)^Lw;iAPx$5xKPXT7B35;++&v7#;PvA@0IXIC>qOMOuF;-ElF z`q#s{mduj0M~7Xd57Rb*bk2KtE7$_)(CFcp4W-#$(Z;nLolzwp=}0x54^g`gg4~DE zo$Am_ZlV;tsmc5%OAK&qGL>+fQpe6z|HoyS@gI?i1;fz=_$(%g40`W7GP*)C50(sJ z>%_S3*ZgA!_ye50zRwHdi!%rHdVy=B+*A*cs_{%~{3hmA&dPS?^mgV@cknhTBWp{s zm?@IJsV%zgv=(YyH8%y(+gU3Fg{?|y%AwM&P%Umg>r$bsnkEL18!kSF@0_om3wnE! zuZXmy-hR)zAZ(Q|1$I;6=pF|AYsS^f8evZTvnp3CTxpe)w@3t|Xozy5i>6@y0D9&T zkkB{gISID5nRHt+Sd|=zqZx9|%)pg=zAOy@fJlGa6`UJ-$|Do z>BxN%eHD8r#_!`l5x=y5&u^jsRD=%~0Qoc;IFg>w-^;?I)cz6pt$IS*6iVrHUfjIK zpLZ6=>RO#oBdy00(Q(&?5!*9cH(Bu&Wvz7CqQL#p)27bGjnJd)h(UpL52WN_&o~IC z$Zj}s>eD=;d_l9?lvkFWdd}%>k99_D&_5qK;3s~_nMWv+LQb@pk5GhtJ0LNk3Vn4!u|;lO6lX*&?%l6pECcO_?=dSHVj38fimtMTIZ) z9$?i!LT6UI?Iv4+TA?zyZ`oBd5Grj>?ut$diMKdSiH)xYN?t7qkK0{)p4cCT!IQwa zDYZ)Zt9eI&>Xl9S_N%ewPskVEnRnh^6wP zngawH0)ad-_pK|_B7q5TPskoUP;2zi3TesJFl5LoYGjg?ub`>H@A!@ch1T)oZI4&b z{^jXm&zspibReOBvNGtht7Cg>n8262R@V*R%ad`)!pZ0M*Hzam=kt5}3QRvP%HqH~ zyq)mV&U1we66s7OV>cSLBJ{OLM-g}qEmHG7{6>!uB>85==vmiePnZF)pPooL!(>P> zmdXS}Qf<~05u?8$l$%*tgB-J4f&7--_i#o1W@nTsra>FLvd?6*Hxh>e=*R;MgSt95 zf=C4(ZIFoJSt_Ag>r3<_w=KmbpGAI4IaG&Fj5XLm8N(Dw6$&3g! zQBwnSZU+s`_$D3qg1S}_uOS=iV|+g~r*J6}OX9>QQ7Sz3^>gOVM~DBC$d z9^G%3Io;Wp+`a|I?QcO6#5Vuo)2#o)g39c{^B$CE!BG|+R4sy6^5_#d`@Q*R}%M;35W8W^=(wGmS9CpEpjc`pauEG-<_5ah)ED?Bp!olU7x91Lh0{ik zpBf7QFgF7LVE=`ef6>L*-p-Z5_J49q@c(;mx#Y99-;hk)hDraLZG;I?79R6ll_v@7 zvohhDtD(n9%#u~N#s-Q>Z7LSUA`3WreVsb=e*UgJgIOz*jF3P0fy8MUhi!t$9;R?$b$?bb*I>mPS|;jD%ymor?2LkH+B$W$ zcpJ<%-l+YZJbFkNW{#yX=xDeoi|pK1E3vcOf(OYY?RJxEC*aF!-fZ9(@QeJ;QGqaa z@bzY3>hRTp1l1-8=NM4S#MJpJcZwslsv}SR^>U|!`w5j zZ{88}_vg=5Xy0Ait(M#QM>*GagGFhR%}m+1Amsgz{^EE!3KVNT&4Os&j(mxCiLYrO z_)6s#$#41%GMNR4vEB)pi*i&blTv+qL*zp;SZh#c^u804*)%WLxP*@Tc<>c z3yT|H@8&(k&-J5mXK+VB!z!#D-8YdVU9=j7oQY+0m5k{NkmKPZf-G_w)7Zy6OR8=* zHldXXV3KKbX+2c`iPVZJ2ypgj0iCDTT55BKoMudaBb-!^n+_d#QrI@_qDw`%3~m31 zZn?(}MteUvxukN5Z5pVjCsWO?`E5n3j^O4wrgVF|N^e_u_cts)tznSa5eY8lt+4e& z#RwCMp?2tTtrT7eG%ILmwr zeq?F~j8|;4JHeGYbtSA!q)26k*qUyJQV!A|0W)Fl;bSjwcG+k!zB9pXVO4sX`UaW$ z5>BQH7CN51#9Q90qZX8~E2`lR<$`5~HN8%@Eo!^d2-5I|9T)7*1$!jOMfz|T3u?iN zM;98@wirL5dMszG5x!kLfcN)6T{$nl%6jH{7BVKq)dgH*y;EDPOa6|d!~EPbwOZTl zfJvoff-?O}ju?>eXD1n9W>lNJ`Nm3iT6_Th zuAbv8VOP+99bJD$$l`0ykrTw^_Rz$78s7lniVhTfiB91|2kYhD`N{LGQ!d>c`72-3 ziSUn;&~LqP=GLQug^C^_Vgh%f6y0!wu6`1 z)G-Cym3Ipwr?=-9*XHM!`LnC5M8J5-O5oJw`c)hk!k;n@oX5V{gj=lHGx)pmm23ow zzd7`vtDQXK4HMHdeofnlFdt`mXhZp|H=>#MKM>?@F&I=s4wy`>=g+ z42`nS4p=M_lRn?B%y8?Mtqe;Y+8@=CzKbv*of5u*jg!R)%!gxpi*QK97m2BxYf)0& zKb*wz;I?}Ne_M_Qe+4zX8oml~1?Hnc`6Ww-Jod*S2leG5OsZwPSR=EKd1z^gpumyr z%=q^lP0{IATc1nZl_q{sDrets`+rQX#svvPN>i&x0F7lqeasD}=`O+2mZ5k$kN!V|1c^&YLFmZk9*~uZ~`^pd z4@rMp=IHIuQsKaNtu#-!c)IyUj7DAEi>)<>kk(jbA-U_c^UKKHP&Gr+iiRiDERd-aq zh+P|5&?=vd1lEO5l}SL%lD@Ye#7PX^oYQtw>jBc-Z=_4(sXCe%|a5Z%X@_c`t~jZpY!8Khe=AhRrA} ztx`6GI;tYfd6Ax|U5%-O4AliIh7rMSS_~nWQ>}ubO_!*RxYc6svR_&7iPOS*W)rT{ z{sTocP^EJj(@gPCp1K-?;j%PaEh@@)!S@RWS(M>C-QGa)YG41P1XAB$`1cv0Lp|ML zd8wKflNxdLocgrDNtC1?R@gGMwVW( zv#~D9Jn7-T0$WdE1#5?-NtV=~N*Q^+xmWZQNqPky8P4;T^IgQw66Gt+JN8S?HP@lR z!u}C*GlG>z)s;bj=%uSps-m2MY8 z8mS}lGXRe!RTk&Sqq-(Ci@8+K@|j%V*I9Gx$iq44a=E zZRXBV%M80qLPqTLfy=5ZQV}Gfdm#%dE8|~I#D^GWrsN{OQ$nG^m zZEE`6?L*6KK{A+aiIt{keG)%dAC#ZmfoiNC*~vMOb>QlZa?@hOLoTZaCI~e2X?Q|q z8$a|@mh`}Asz+6%;na*;Wur}OO}=q%^wOZFY0z5C4#~S25o22u6r|HY*9*TLf9^QH zWB}I>1`gA8kw$#zu8Rj=&3;UWX+!eNSn8sbLMZ`SYL zn=Pl`fs}ErPIr&4@;z(QW38QB9-F?IV`BrCS-dt$_q#AGInEUOK(APurk7-s+4fGN zHr4><)@Vcq;2CoXVg_Qv`^v^FJ^V`Hc;hv^`vKVJU#=7#-n-r(2)r($PRC7jQEmlj z$R{q?gCXC1LXXw^)Kk+ls#xyf%%`&rFw{xuoHE^CSVM=tTUd4C!(g8lP_$ zFJG2gNt(vm76ED}n);19GcJq}s5LC@kB44z&p_k3#$47Ju_|NKVrqfCL#79(Jac)003n)Ho5FmCLLucf?$~yaQULXV?J$|;#>DWYy{&u;Rb!6rrStyGTf}a7Q z^5Rk1NzOB|+}6?OAVt|z#Ad*TiPImk|F51y=(vY|R zx4ksxT6MpP8$#i?wb|6e^>RJM=;nTftxj2fcz4tdXJ2kTErLqm3H>V|ai z4}S}`&C5B;yKTD4SCF)uhmH16Y)e`o<|Bz*nn5y?IO07&+{>X16>u4J_Up_bw?(+GRfjY;Xj`uoKS-D<5` z-L_GmuLRUze5{M-j=IsV1hJ#LdnjrV6t(I$qdFvrRgbTf&da^gs}bmuG6D8ew+ajmg4rk>39hFvuwM4 zt|j}Ornf`Sha${!v_32_{G@XjJ^xmi*x^dv_H^9G*LG-4sZRz`E3(*MJNED|o*nX0zN$Qs-T%wj8mXE&byq zMD8g+;Np{?)ouGtqQWP^JD*~KsG<&7Uv}WMb>vxaWeK6XPJ=T}IUV+=f&06!wXjS; z4i9DT=9-&=zXHp3y1%$uc`yzjY)9n#GvoruL$-4k>(jX}3AMKs#&WvqU8-2Q%%-yJ z;1^yIqe8%gEnd-YCCPD$v1;B#OX+^BjPPn;g&hG2U@G>Be#B8N+4}C#$GmIAx8?JEk|jlYP2*=hR+NO+=l=0vr=~!=)MWas;{X{(2!D>!x-DX zh9-EiLLq7~jzi|l^s|V0GJ-BEf7f7lBvBu3)@VefffTE|hUsHc{~$s^4WZmkCb_nS zAB-0BXf##|C3y(6xY#l9U0&}R^XE+Y8qX7j%V>PPC8LVz7PP#AlD1}4M0y54v|v<> z{Z}6CBBuP)i0kbes+#taHsP4ZbRm~_s*$X31U75CX*VjcjJO3O2eWn=3&y%H*5W)zUjYIcQx^7 z1YYh-y(2JsRXgW{21biscnn9&A|0WTBLq#?WiIp{OKbuXXp>ZS|?(zog175NCKj6hNK{q;Q5dP9?Fpevn3hD+iR`2!Klnfuz*MP{iSAXQ5-4S7^yCK^u?fO` zZzF$Aq9YA8TS}wNNcAh-SdPvnp`RGhJ9L9n!Pkwq?rDLGcfOrMa z`|{D(#~T|sHb8FhUH0SV!KqU;u0$O7?9qp9$6MFVG+gT54blp1MM)eQeGVFV&~Uz2 z>rS1?PU~M`WOS)o)bJ{0L$GViE0f{M|C}0{DYUKj{>(E-)+%NT5{=-26*ZQqd-X*5 z^pabY<$M{frMfE2q0na)f+6##B)~C@|C}jxW_$~ZnkIbVho8U9%KiFt`uTXAJvrk( zT-^2J&!-66wf|Jz$b07BM?F6WHhw=s+a!*?;yA9jP4D?bCtPQMpOf+QfcY&z32ye7 z;=*Ql9@z6{>w4dE?6IyJ)-A)i6vG~I_gC|&i*1Z2k;>SgBAGmRI|>}~^;kekOZXzY zEKYTPK8;b(KX!sZuMiu%BdAo>{+7HtD&%yxQv*L>%KiY|OXHlchZg)V&TL1oo3qKc z-C<%hX>Pw5GK|MTu6SiuPk)A^Ajt~Ks=!G&BgUjqPexIv+20ZHZ&z}w>~p_&7O)EO z1caB#HdXkPuX$ygOFYt;Fp_<$PZHL{eXgC_M-C51+D6VDnV-v&l)`;%PS96J*c62M z<9srzb=K0{yA?BBO>t>%O?kjyD`|5P@eRpwwE$J1fZt)6mH9#FUX+$85(?S#NwRlH z@y6MUs$z@VW*LJJNr@ppg(!Dterc@r(kUhs_6rriCudD#%^QO{JEUjauTH^y8eICb z6;AH88J_a&i;e83Zz1r#3lBDexLCCgWAe-;PH3y&!I2D*pu8E!?r=y^S8qp8*inR; zTzTc`19pHpT1Y3HkUGyV>a#rK7>b$-ziV$1LT~U+y;Rp^;@j~)np$i3!Vh>T#)eBF zW185bV8h%cr>&{hP~JKeCNeq?pp4`*2wz42K1X(F6n>GXQGM8jUVbVz{KXhvk{ir+@oGBgyzl+>}9XlZEtoo3hR6PsES$x z2jT_EH3IBNa6{OY$9A)v?=KPX)>WCCa$7gScMIL5ooD-ldDd$>j)yg0e;%;G6tV0| zcMcg(HR?fll5ETzda7@uI{j&swj^Ax$|eMZ>8i@ECJh_{jVdgvl|w-qv1moI7>JhF zX*Ku)ZOserygHlC%Y<1CtFR1jTYp}TGs4T+yZ}Rrw-SDB6u4u|BaV50EEe9i{?H;U ziHj|Z`?^-#@!wg)W~w&Ik5-$X87L^nuDZ>T=>om$`3ogC*nH7L5Ubj2DT(X`wA}-2 zn2K2(g&`f4GCyykS(XU>&a$2r1YDs@kGpdz6?pZ6DDM&@@ZJX0;Sqpd0ms=_TyHd1 zRb91(^(}JdsB{ylxj&?HH)V=L6Z!H)=6Uz0#WMe_Sf8@5Pbt?@RQ4H_&4#TvOu3RM)JP-W(sg zDW4d=z4ipO+`p zY00=CwTB`Ti@zpM^yNz_AK5{LwLR^|qgDL|KeD}D$J1r#9J0rkIJsD_Q6}`JVzrVpx?F1eg)3m zA&*Bp69#oz7;{xpIdZ}Kyk~N#WiM`-SC34mxkcqWvBArxV3%!-5Y>Kgie# zdN920HKh$PHt4-z!5ObncNxV_o$?)|?AQ?5HJ{3DYba@|K(SA!?MU}Y$@xlUXI2iF zec=!9S^B*7UG~eL9fd+YCGR?brr$){5FbzW1Tu5~@-d`vYbZrUTQ%Ugd z$BF-tn8O~yCZe4kSDgNmN73>$V8n_Fpl5z!5m|phF_BSLBE;i5D996k)xXYTHNh^T z`~oP-fPoW2{D1Lf*#EdQ0N|gC07U`+IsKos8PxwxoBbc8*?(*P@3GH+Yj*!5+5T$? x^iS?TL!kd3x&Q6#|CXaB`{(!n^7%i#|M>iW=|MsN=Q9xh*8RV#Pw}7I{{>mxP2T_j From d9031844da2ed4c085db57d9793ef1b5b1913c3e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Feb 2014 00:13:55 +0400 Subject: [PATCH 16/76] Unused includes removed --- src/modules/mc_att_control/mc_att_control_main.cpp | 2 -- src/modules/mc_pos_control/mc_pos_control_main.cpp | 2 -- .../position_estimator_inav/position_estimator_inav_main.c | 3 --- 3 files changed, 7 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 01902ed0cf..24226880ed 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -53,11 +53,9 @@ #include #include #include -#include #include #include #include -#include #include #include #include diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 25d34c872d..b06655385a 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -51,7 +51,6 @@ #include #include #include -#include #include #include #include @@ -68,7 +67,6 @@ #include #include #include -#include #include #include #include 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 bf4f7ae974..ad363efe06 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -42,14 +42,11 @@ #include #include #include -#include #include #include #include #include #include -#include -#include #include #include #include From 98ee73463f428b420d4aeb44af4a7a90d8d40e41 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:14:40 +0100 Subject: [PATCH 17/76] Removed obsolete ROMFS folder for removed logging build. The logging makefile was removed in 9a54c7c6. --- ROMFS/px4fmu_logging/init.d/rcS | 88 -------------------------- ROMFS/px4fmu_logging/logging/conv.zip | Bin 10087 -> 0 bytes 2 files changed, 88 deletions(-) delete mode 100644 ROMFS/px4fmu_logging/init.d/rcS delete mode 100644 ROMFS/px4fmu_logging/logging/conv.zip diff --git a/ROMFS/px4fmu_logging/init.d/rcS b/ROMFS/px4fmu_logging/init.d/rcS deleted file mode 100644 index 7b88567197..0000000000 --- a/ROMFS/px4fmu_logging/init.d/rcS +++ /dev/null @@ -1,88 +0,0 @@ -#!nsh -# -# PX4FMU startup script for logging purposes -# - -# -# Try to mount the microSD card. -# -echo "[init] looking for microSD..." -if mount -t vfat /dev/mmcsd0 /fs/microsd -then - echo "[init] card mounted at /fs/microsd" - # Start playing the startup tune - tone_alarm start -else - echo "[init] no microSD card found" - # Play SOS - tone_alarm error -fi - -uorb start - -# -# Start sensor drivers here. -# - -ms5611 start -adc start - -# mag might be external -if hmc5883 start -then - echo "using HMC5883" -fi - -if mpu6000 start -then - echo "using MPU6000" -fi - -if l3gd20 start -then - echo "using L3GD20(H)" -fi - -if lsm303d start -then - set BOARD fmuv2 -else - set BOARD fmuv1 -fi - -# Start airspeed sensors -if meas_airspeed start -then - echo "using MEAS airspeed sensor" -else - if ets_airspeed start - then - echo "using ETS airspeed sensor (bus 3)" - else - if ets_airspeed start -b 1 - then - echo "Using ETS airspeed sensor (bus 1)" - fi - fi -fi - -# -# Start the sensor collection task. -# IMPORTANT: this also loads param offsets -# ALWAYS start this task before the -# preflight_check. -# -if sensors start -then - echo "SENSORS STARTED" -fi - -sdlog2 start -r 250 -e -b 16 - -if sercon -then - echo "[init] USB interface connected" - - # Try to get an USB console - nshterm /dev/ttyACM0 & -fi \ No newline at end of file diff --git a/ROMFS/px4fmu_logging/logging/conv.zip b/ROMFS/px4fmu_logging/logging/conv.zip deleted file mode 100644 index 7cb837e5666f51eca7ed803dfef4581f01bec1f3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10087 zcmaL7V{j!v*Zq6qi8b-WwoYu@b~3Ruv27bCwrx&qn-kl{1b3eIR^58)|K5A6t7~_E z=vCEK>&x2vrzisf`5gcNd;_41Ac~;1hZwjZ007J^000u;2f)e1#@?L8z{JJYfx*E; zO%)aZK`{rbEVu%z?BWg&0E2u40|5T#eYduc{RTVwSLf&Vs=&Ob3ipT&^VL98!Sy1Y z`jRQoLtoBNXx?aYwOR?Vo0Bcn=lM9cNHVfu(FC6YGInbJ!=0DlI%Mz9e(ia~%Nx6q zfl3ScYmK(K4KOmwMkJ7^rm`bXNH9?@2Lod)Dp+lHynv?9F6TIVDKiV;rFkIKYz;3Bf5Ch-qX|N?qkU9?pV<-K9z`#ZbF6`CW_Fi+w2FcLJukytO^TKNyog*Lu3Qj0$T}|*x*y#1#v+PKorgM^R zci~g&oh8_tM7z^CS6E7wz_-$h)(;mciFG37LA`wkS-0%~oJ8JYPK(q+;$$+}g^O5* zQbUwNC6r(`ItwsY5&3YpaT?7{tX*5Z8Ucz)2=0?cNd6PRL*XexdQnJf+{VsQX0v{FM`>qGo((^C9 zoQa$tpBp0biCrt#z`waxLtQ%8>Cw9jl=iIRlszR~JIPo`;~ei~`+Uj!kU$U-O)J>5papx6c~e1D-*AboN=+cARG*U2`IK;r z`dBCl>^h2Giz5tO-#;q$%LM2uImOFTF z15Tl2KU2flP8UMuZ0IQMfdE;xIr1Vx0MiW7vI=BEJUgqlMso3ED2~d;fTGyTPYxg; z9-6ci8j)y=qRNm|_k;7W;z9R>sv+M;G|o!!ry4r$uT&H-P`xgZOV7b+xMlJ3UHAt| z@7~zlQ}`x{vTAg);NzH{a`jkJEw8Y^Aqow%jTzZ6eJX`%$d+i6O(s1yy~SbG7)l%1 zU(w688v4u)Egv_do{)S*&dm!u;3+hy7QZUW@i9_CtH83k%?;#8{3Zc&kDCRzBRx1g z8yx@Iln4M4SsiA=;>rui0I&E5fR+6#r$DL_^wrW~&v_!&RXQ>ur zZ*mMrdrSxh;upU$c#_rI5yyqBBu`RsFqv_g8ZWI-DqQ98XN2c)Lp5Zyq1#n*GB$jB zmnCIsWFz9e7G?WsWp=9L6kZ)^m%WNtwFKj4zfVAXsAKLHu*%Dy!S-}J@U*lcw$6+0mql^qO1PMlw9WCzcc5TmM zFB76W{8^t4>+G*F8kc||q0jo!2o_r^p+}&&p&9+Knt1+gLJrI_$tJMo;Kh;$c|?RB69 zO@YF&0_P~_y{kw{t#mtt+WFgEw^QxQpj_{+?oPHH=-8Z6V0iG~kRkI>x3a zL{Mx}cWib{tDX{_YD`_MAgqCDbflvmIW#frWum#j6n0?2MR4AQ_+ZNU$vAfE5S590 zV7-e{p)gTEWpB9}*6+N>G7du#Gqvc>nj3kwn1VtpOdRuIqr0yVf#rTP*8ZkytGX0Z z!=}Art+{j;bJfYDpo4pfYudZd&p6Y1z6v>f=Je*3TK7w1G=j=O9>IdXn5Tlz!GCOY z6{>`>ekR}{AXS^b8)^Lw;iAPx$5xKPXT7B35;++&v7#;PvA@0IXIC>qOMOuF;-ElF z`q#s{mduj0M~7Xd57Rb*bk2KtE7$_)(CFcp4W-#$(Z;nLolzwp=}0x54^g`gg4~DE zo$Am_ZlV;tsmc5%OAK&qGL>+fQpe6z|HoyS@gI?i1;fz=_$(%g40`W7GP*)C50(sJ z>%_S3*ZgA!_ye50zRwHdi!%rHdVy=B+*A*cs_{%~{3hmA&dPS?^mgV@cknhTBWp{s zm?@IJsV%zgv=(YyH8%y(+gU3Fg{?|y%AwM&P%Umg>r$bsnkEL18!kSF@0_om3wnE! zuZXmy-hR)zAZ(Q|1$I;6=pF|AYsS^f8evZTvnp3CTxpe)w@3t|Xozy5i>6@y0D9&T zkkB{gISID5nRHt+Sd|=zqZx9|%)pg=zAOy@fJlGa6`UJ-$|Do z>BxN%eHD8r#_!`l5x=y5&u^jsRD=%~0Qoc;IFg>w-^;?I)cz6pt$IS*6iVrHUfjIK zpLZ6=>RO#oBdy00(Q(&?5!*9cH(Bu&Wvz7CqQL#p)27bGjnJd)h(UpL52WN_&o~IC z$Zj}s>eD=;d_l9?lvkFWdd}%>k99_D&_5qK;3s~_nMWv+LQb@pk5GhtJ0LNk3Vn4!u|;lO6lX*&?%l6pECcO_?=dSHVj38fimtMTIZ) z9$?i!LT6UI?Iv4+TA?zyZ`oBd5Grj>?ut$diMKdSiH)xYN?t7qkK0{)p4cCT!IQwa zDYZ)Zt9eI&>Xl9S_N%ewPskVEnRnh^6wP zngawH0)ad-_pK|_B7q5TPskoUP;2zi3TesJFl5LoYGjg?ub`>H@A!@ch1T)oZI4&b z{^jXm&zspibReOBvNGtht7Cg>n8262R@V*R%ad`)!pZ0M*Hzam=kt5}3QRvP%HqH~ zyq)mV&U1we66s7OV>cSLBJ{OLM-g}qEmHG7{6>!uB>85==vmiePnZF)pPooL!(>P> zmdXS}Qf<~05u?8$l$%*tgB-J4f&7--_i#o1W@nTsra>FLvd?6*Hxh>e=*R;MgSt95 zf=C4(ZIFoJSt_Ag>r3<_w=KmbpGAI4IaG&Fj5XLm8N(Dw6$&3g! zQBwnSZU+s`_$D3qg1S}_uOS=iV|+g~r*J6}OX9>QQ7Sz3^>gOVM~DBC$d z9^G%3Io;Wp+`a|I?QcO6#5Vuo)2#o)g39c{^B$CE!BG|+R4sy6^5_#d`@Q*R}%M;35W8W^=(wGmS9CpEpjc`pauEG-<_5ah)ED?Bp!olU7x91Lh0{ik zpBf7QFgF7LVE=`ef6>L*-p-Z5_J49q@c(;mx#Y99-;hk)hDraLZG;I?79R6ll_v@7 zvohhDtD(n9%#u~N#s-Q>Z7LSUA`3WreVsb=e*UgJgIOz*jF3P0fy8MUhi!t$9;R?$b$?bb*I>mPS|;jD%ymor?2LkH+B$W$ zcpJ<%-l+YZJbFkNW{#yX=xDeoi|pK1E3vcOf(OYY?RJxEC*aF!-fZ9(@QeJ;QGqaa z@bzY3>hRTp1l1-8=NM4S#MJpJcZwslsv}SR^>U|!`w5j zZ{88}_vg=5Xy0Ait(M#QM>*GagGFhR%}m+1Amsgz{^EE!3KVNT&4Os&j(mxCiLYrO z_)6s#$#41%GMNR4vEB)pi*i&blTv+qL*zp;SZh#c^u804*)%WLxP*@Tc<>c z3yT|H@8&(k&-J5mXK+VB!z!#D-8YdVU9=j7oQY+0m5k{NkmKPZf-G_w)7Zy6OR8=* zHldXXV3KKbX+2c`iPVZJ2ypgj0iCDTT55BKoMudaBb-!^n+_d#QrI@_qDw`%3~m31 zZn?(}MteUvxukN5Z5pVjCsWO?`E5n3j^O4wrgVF|N^e_u_cts)tznSa5eY8lt+4e& z#RwCMp?2tTtrT7eG%ILmwr zeq?F~j8|;4JHeGYbtSA!q)26k*qUyJQV!A|0W)Fl;bSjwcG+k!zB9pXVO4sX`UaW$ z5>BQH7CN51#9Q90qZX8~E2`lR<$`5~HN8%@Eo!^d2-5I|9T)7*1$!jOMfz|T3u?iN zM;98@wirL5dMszG5x!kLfcN)6T{$nl%6jH{7BVKq)dgH*y;EDPOa6|d!~EPbwOZTl zfJvoff-?O}ju?>eXD1n9W>lNJ`Nm3iT6_Th zuAbv8VOP+99bJD$$l`0ykrTw^_Rz$78s7lniVhTfiB91|2kYhD`N{LGQ!d>c`72-3 ziSUn;&~LqP=GLQug^C^_Vgh%f6y0!wu6`1 z)G-Cym3Ipwr?=-9*XHM!`LnC5M8J5-O5oJw`c)hk!k;n@oX5V{gj=lHGx)pmm23ow zzd7`vtDQXK4HMHdeofnlFdt`mXhZp|H=>#MKM>?@F&I=s4wy`>=g+ z42`nS4p=M_lRn?B%y8?Mtqe;Y+8@=CzKbv*of5u*jg!R)%!gxpi*QK97m2BxYf)0& zKb*wz;I?}Ne_M_Qe+4zX8oml~1?Hnc`6Ww-Jod*S2leG5OsZwPSR=EKd1z^gpumyr z%=q^lP0{IATc1nZl_q{sDrets`+rQX#svvPN>i&x0F7lqeasD}=`O+2mZ5k$kN!V|1c^&YLFmZk9*~uZ~`^pd z4@rMp=IHIuQsKaNtu#-!c)IyUj7DAEi>)<>kk(jbA-U_c^UKKHP&Gr+iiRiDERd-aq zh+P|5&?=vd1lEO5l}SL%lD@Ye#7PX^oYQtw>jBc-Z=_4(sXCe%|a5Z%X@_c`t~jZpY!8Khe=AhRrA} ztx`6GI;tYfd6Ax|U5%-O4AliIh7rMSS_~nWQ>}ubO_!*RxYc6svR_&7iPOS*W)rT{ z{sTocP^EJj(@gPCp1K-?;j%PaEh@@)!S@RWS(M>C-QGa)YG41P1XAB$`1cv0Lp|ML zd8wKflNxdLocgrDNtC1?R@gGMwVW( zv#~D9Jn7-T0$WdE1#5?-NtV=~N*Q^+xmWZQNqPky8P4;T^IgQw66Gt+JN8S?HP@lR z!u}C*GlG>z)s;bj=%uSps-m2MY8 z8mS}lGXRe!RTk&Sqq-(Ci@8+K@|j%V*I9Gx$iq44a=E zZRXBV%M80qLPqTLfy=5ZQV}Gfdm#%dE8|~I#D^GWrsN{OQ$nG^m zZEE`6?L*6KK{A+aiIt{keG)%dAC#ZmfoiNC*~vMOb>QlZa?@hOLoTZaCI~e2X?Q|q z8$a|@mh`}Asz+6%;na*;Wur}OO}=q%^wOZFY0z5C4#~S25o22u6r|HY*9*TLf9^QH zWB}I>1`gA8kw$#zu8Rj=&3;UWX+!eNSn8sbLMZ`SYL zn=Pl`fs}ErPIr&4@;z(QW38QB9-F?IV`BrCS-dt$_q#AGInEUOK(APurk7-s+4fGN zHr4><)@Vcq;2CoXVg_Qv`^v^FJ^V`Hc;hv^`vKVJU#=7#-n-r(2)r($PRC7jQEmlj z$R{q?gCXC1LXXw^)Kk+ls#xyf%%`&rFw{xuoHE^CSVM=tTUd4C!(g8lP_$ zFJG2gNt(vm76ED}n);19GcJq}s5LC@kB44z&p_k3#$47Ju_|NKVrqfCL#79(Jac)003n)Ho5FmCLLucf?$~yaQULXV?J$|;#>DWYy{&u;Rb!6rrStyGTf}a7Q z^5Rk1NzOB|+}6?OAVt|z#Ad*TiPImk|F51y=(vY|R zx4ksxT6MpP8$#i?wb|6e^>RJM=;nTftxj2fcz4tdXJ2kTErLqm3H>V|ai z4}S}`&C5B;yKTD4SCF)uhmH16Y)e`o<|Bz*nn5y?IO07&+{>X16>u4J_Up_bw?(+GRfjY;Xj`uoKS-D<5` z-L_GmuLRUze5{M-j=IsV1hJ#LdnjrV6t(I$qdFvrRgbTf&da^gs}bmuG6D8ew+ajmg4rk>39hFvuwM4 zt|j}Ornf`Sha${!v_32_{G@XjJ^xmi*x^dv_H^9G*LG-4sZRz`E3(*MJNED|o*nX0zN$Qs-T%wj8mXE&byq zMD8g+;Np{?)ouGtqQWP^JD*~KsG<&7Uv}WMb>vxaWeK6XPJ=T}IUV+=f&06!wXjS; z4i9DT=9-&=zXHp3y1%$uc`yzjY)9n#GvoruL$-4k>(jX}3AMKs#&WvqU8-2Q%%-yJ z;1^yIqe8%gEnd-YCCPD$v1;B#OX+^BjPPn;g&hG2U@G>Be#B8N+4}C#$GmIAx8?JEk|jlYP2*=hR+NO+=l=0vr=~!=)MWas;{X{(2!D>!x-DX zh9-EiLLq7~jzi|l^s|V0GJ-BEf7f7lBvBu3)@VefffTE|hUsHc{~$s^4WZmkCb_nS zAB-0BXf##|C3y(6xY#l9U0&}R^XE+Y8qX7j%V>PPC8LVz7PP#AlD1}4M0y54v|v<> z{Z}6CBBuP)i0kbes+#taHsP4ZbRm~_s*$X31U75CX*VjcjJO3O2eWn=3&y%H*5W)zUjYIcQx^7 z1YYh-y(2JsRXgW{21biscnn9&A|0WTBLq#?WiIp{OKbuXXp>ZS|?(zog175NCKj6hNK{q;Q5dP9?Fpevn3hD+iR`2!Klnfuz*MP{iSAXQ5-4S7^yCK^u?fO` zZzF$Aq9YA8TS}wNNcAh-SdPvnp`RGhJ9L9n!Pkwq?rDLGcfOrMa z`|{D(#~T|sHb8FhUH0SV!KqU;u0$O7?9qp9$6MFVG+gT54blp1MM)eQeGVFV&~Uz2 z>rS1?PU~M`WOS)o)bJ{0L$GViE0f{M|C}0{DYUKj{>(E-)+%NT5{=-26*ZQqd-X*5 z^pabY<$M{frMfE2q0na)f+6##B)~C@|C}jxW_$~ZnkIbVho8U9%KiFt`uTXAJvrk( zT-^2J&!-66wf|Jz$b07BM?F6WHhw=s+a!*?;yA9jP4D?bCtPQMpOf+QfcY&z32ye7 z;=*Ql9@z6{>w4dE?6IyJ)-A)i6vG~I_gC|&i*1Z2k;>SgBAGmRI|>}~^;kekOZXzY zEKYTPK8;b(KX!sZuMiu%BdAo>{+7HtD&%yxQv*L>%KiY|OXHlchZg)V&TL1oo3qKc z-C<%hX>Pw5GK|MTu6SiuPk)A^Ajt~Ks=!G&BgUjqPexIv+20ZHZ&z}w>~p_&7O)EO z1caB#HdXkPuX$ygOFYt;Fp_<$PZHL{eXgC_M-C51+D6VDnV-v&l)`;%PS96J*c62M z<9srzb=K0{yA?BBO>t>%O?kjyD`|5P@eRpwwE$J1fZt)6mH9#FUX+$85(?S#NwRlH z@y6MUs$z@VW*LJJNr@ppg(!Dterc@r(kUhs_6rriCudD#%^QO{JEUjauTH^y8eICb z6;AH88J_a&i;e83Zz1r#3lBDexLCCgWAe-;PH3y&!I2D*pu8E!?r=y^S8qp8*inR; zTzTc`19pHpT1Y3HkUGyV>a#rK7>b$-ziV$1LT~U+y;Rp^;@j~)np$i3!Vh>T#)eBF zW185bV8h%cr>&{hP~JKeCNeq?pp4`*2wz42K1X(F6n>GXQGM8jUVbVz{KXhvk{ir+@oGBgyzl+>}9XlZEtoo3hR6PsES$x z2jT_EH3IBNa6{OY$9A)v?=KPX)>WCCa$7gScMIL5ooD-ldDd$>j)yg0e;%;G6tV0| zcMcg(HR?fll5ETzda7@uI{j&swj^Ax$|eMZ>8i@ECJh_{jVdgvl|w-qv1moI7>JhF zX*Ku)ZOserygHlC%Y<1CtFR1jTYp}TGs4T+yZ}Rrw-SDB6u4u|BaV50EEe9i{?H;U ziHj|Z`?^-#@!wg)W~w&Ik5-$X87L^nuDZ>T=>om$`3ogC*nH7L5Ubj2DT(X`wA}-2 zn2K2(g&`f4GCyykS(XU>&a$2r1YDs@kGpdz6?pZ6DDM&@@ZJX0;Sqpd0ms=_TyHd1 zRb91(^(}JdsB{ylxj&?HH)V=L6Z!H)=6Uz0#WMe_Sf8@5Pbt?@RQ4H_&4#TvOu3RM)JP-W(sg zDW4d=z4ipO+`p zY00=CwTB`Ti@zpM^yNz_AK5{LwLR^|qgDL|KeD}D$J1r#9J0rkIJsD_Q6}`JVzrVpx?F1eg)3m zA&*Bp69#oz7;{xpIdZ}Kyk~N#WiM`-SC34mxkcqWvBArxV3%!-5Y>Kgie# zdN920HKh$PHt4-z!5ObncNxV_o$?)|?AQ?5HJ{3DYba@|K(SA!?MU}Y$@xlUXI2iF zec=!9S^B*7UG~eL9fd+YCGR?brr$){5FbzW1Tu5~@-d`vYbZrUTQ%Ugd z$BF-tn8O~yCZe4kSDgNmN73>$V8n_Fpl5z!5m|phF_BSLBE;i5D996k)xXYTHNh^T z`~oP-fPoW2{D1Lf*#EdQ0N|gC07U`+IsKos8PxwxoBbc8*?(*P@3GH+Yj*!5+5T$? x^iS?TL!kd3x&Q6#|CXaB`{(!n^7%i#|M>iW=|MsN=Q9xh*8RV#Pw}7I{{>mxP2T_j From 1afa53a159ee247a1c57ca59912077c5076c3997 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:15:35 +0100 Subject: [PATCH 18/76] Cleanup: Moved sdlog2 file conversion scripts to separate folder. --- Tools/{ => sdlog2}/README.txt | 0 Tools/{ => sdlog2}/logconv.m | 1070 ++++++++++++++--------------- Tools/{ => sdlog2}/sdlog2_dump.py | 0 3 files changed, 535 insertions(+), 535 deletions(-) rename Tools/{ => sdlog2}/README.txt (100%) rename Tools/{ => sdlog2}/logconv.m (97%) rename Tools/{ => sdlog2}/sdlog2_dump.py (100%) diff --git a/Tools/README.txt b/Tools/sdlog2/README.txt similarity index 100% rename from Tools/README.txt rename to Tools/sdlog2/README.txt diff --git a/Tools/logconv.m b/Tools/sdlog2/logconv.m similarity index 97% rename from Tools/logconv.m rename to Tools/sdlog2/logconv.m index c416b8095e..e19c97fa3c 100644 --- a/Tools/logconv.m +++ b/Tools/sdlog2/logconv.m @@ -1,535 +1,535 @@ -% This Matlab Script can be used to import the binary logged values of the -% PX4FMU into data that can be plotted and analyzed. - -%% ************************************************************************ -% PX4LOG_PLOTSCRIPT: Main function -% ************************************************************************ -function PX4Log_Plotscript - -% Clear everything -clc -clear all -close all - -% ************************************************************************ -% SETTINGS -% ************************************************************************ - -% Set the path to your sysvector.bin file here -filePath = 'log001.bin'; - -% Set the minimum and maximum times to plot here [in seconds] -mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] -maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] - -%Determine which data to plot. Not completely implemented yet. -bDisplayGPS=true; - -%conversion factors -fconv_gpsalt=1; %[mm] to [m] -fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg] -fconv_timestamp=1E-6; % [microseconds] to [seconds] - -% ************************************************************************ -% Import the PX4 logs -% ************************************************************************ -ImportPX4LogData(); - -%Translate min and max plot times to indices -time=double(sysvector.TIME_StartTime) .*fconv_timestamp; -mintime_log=time(1); %The minimum time/timestamp found in the log -maxtime_log=time(end); %The maximum time/timestamp found in the log -CurTime=mintime_log; %The current time at which to draw the aircraft position - -[imintime,imaxtime]=FindMinMaxTimeIndices(); - -% ************************************************************************ -% PLOT & GUI SETUP -% ************************************************************************ -NrFigures=5; -NrAxes=10; -h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively -h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively -h.pathpoints=[]; % Temporary initiliazation of path points - -% Setup the GUI to control the plots -InitControlGUI(); -% Setup the plotting-GUI (figures, axes) itself. -InitPlotGUI(); - -% ************************************************************************ -% DRAW EVERYTHING -% ************************************************************************ -DrawRawData(); -DrawCurrentAircraftState(); - -%% ************************************************************************ -% *** END OF MAIN SCRIPT *** -% NESTED FUNCTION DEFINTIONS FROM HERE ON -% ************************************************************************ - - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -function ImportPX4LogData() - - % ************************************************************************ - % RETRIEVE SYSTEM VECTOR - % ************************************************************************* - % //All measurements in NED frame - - % Convert to CSV - %arg1 = 'log-fx61-20130721-2.bin'; - arg1 = filePath; - delim = ','; - time_field = 'TIME'; - data_file = 'data.csv'; - csv_null = ''; - - if not(exist(data_file, 'file')) - s = system( sprintf('python sdlog2_dump.py "%s" -f "%s" -t"%s" -d"%s" -n"%s"', arg1, data_file, time_field, delim, csv_null) ); - end - - if exist(data_file, 'file') - - %data = csvread(data_file); - sysvector = tdfread(data_file, ','); - - % shot the flight time - time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); - time_s = uint64(time_us*1e-6); - time_m = uint64(time_s/60); - time_s = time_s - time_m * 60; - - disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); - - disp(['logfile conversion finished.' char(10)]); - else - disp(['file: ' data_file ' does not exist' char(10)]); - end -end - -%% ************************************************************************ -% INITCONTROLGUI (nested function) -% ************************************************************************ -%Setup central control GUI components to control current time where data is shown -function InitControlGUI() - %********************************************************************** - % GUI size definitions - %********************************************************************** - dxy=5; %margins - %Panel: Plotctrl - dlabels=120; - dsliders=200; - dedits=80; - hslider=20; - - hpanel1=40; %panel1 - hpanel2=220;%panel2 - hpanel3=3*hslider+4*dxy+3*dxy;%panel3. - - width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width - height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height - - %********************************************************************** - % Create GUI - %********************************************************************** - h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); - h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); - h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); - h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); - - %%Control GUI-elements - %Slider: Current time - h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... - 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); - temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); - set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); - h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... - 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); - - %Slider: MaxTime - h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %Slider: MinTime - h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %%Current data/state GUI-elements (Multiline-edit-box) - h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... - 'HorizontalAlignment','left','parent',h.aircraftstatepanel); - - h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... - 'HorizontalAlignment','left','parent',h.guistatepanel); - -end - -%% ************************************************************************ -% INITPLOTGUI (nested function) -% ************************************************************************ -function InitPlotGUI() - - % Setup handles to lines and text - h.markertext=[]; - templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array - h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively - h.markerline(1:NrAxes)=0.0; - - % Setup all other figures and axes for plotting - % PLOT WINDOW 1: GPS POSITION - h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); - h.axes(1)=axes(); - set(h.axes(1),'Parent',h.figures(2)); - - % PLOT WINDOW 2: IMU, baro altitude - h.figures(3)=figure('Name', 'IMU / Baro Altitude'); - h.axes(2)=subplot(4,1,1); - h.axes(3)=subplot(4,1,2); - h.axes(4)=subplot(4,1,3); - h.axes(5)=subplot(4,1,4); - set(h.axes(2:5),'Parent',h.figures(3)); - - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); - h.axes(6)=subplot(4,1,1); - h.axes(7)=subplot(4,1,2); - h.axes(8)=subplot(4,1,3); - h.axes(9)=subplot(4,1,4); - set(h.axes(6:9),'Parent',h.figures(4)); - - % PLOT WINDOW 4: LOG STATS - h.figures(5) = figure('Name', 'Log Statistics'); - h.axes(10)=subplot(1,1,1); - set(h.axes(10:10),'Parent',h.figures(5)); - -end - -%% ************************************************************************ -% DRAWRAWDATA (nested function) -% ************************************************************************ -%Draws the raw data from the sysvector, but does not add any -%marker-lines or so -function DrawRawData() - % ************************************************************************ - % PLOT WINDOW 1: GPS POSITION & GUI - % ************************************************************************ - figure(h.figures(2)); - % Only plot GPS data if available - if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS) - %Draw data - plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:imaxtime))*fconv_gpslatlong, ... - double(sysvector.GPS_Lon(imintime:imaxtime))*fconv_gpslatlong, ... - double(sysvector.GPS_Alt(imintime:imaxtime))*fconv_gpsalt,'r.'); - title(h.axes(1),'GPS Position Data(if available)'); - xlabel(h.axes(1),'Latitude [deg]'); - ylabel(h.axes(1),'Longitude [deg]'); - zlabel(h.axes(1),'Altitude above MSL [m]'); - grid on - - %Reset path - h.pathpoints=0; - end - - % ************************************************************************ - % PLOT WINDOW 2: IMU, baro altitude - % ************************************************************************ - figure(h.figures(3)); - plot(h.axes(2),time(imintime:imaxtime),[sysvector.IMU_MagX(imintime:imaxtime), sysvector.IMU_MagY(imintime:imaxtime), sysvector.IMU_MagZ(imintime:imaxtime)]); - title(h.axes(2),'Magnetometers [Gauss]'); - legend(h.axes(2),'x','y','z'); - plot(h.axes(3),time(imintime:imaxtime),[sysvector.IMU_AccX(imintime:imaxtime), sysvector.IMU_AccY(imintime:imaxtime), sysvector.IMU_AccZ(imintime:imaxtime)]); - title(h.axes(3),'Accelerometers [m/s²]'); - legend(h.axes(3),'x','y','z'); - plot(h.axes(4),time(imintime:imaxtime),[sysvector.IMU_GyroX(imintime:imaxtime), sysvector.IMU_GyroY(imintime:imaxtime), sysvector.IMU_GyroZ(imintime:imaxtime)]); - title(h.axes(4),'Gyroscopes [rad/s]'); - legend(h.axes(4),'x','y','z'); - plot(h.axes(5),time(imintime:imaxtime),sysvector.SENS_BaroAlt(imintime:imaxtime),'color','blue'); - if(bDisplayGPS) - hold on; - plot(h.axes(5),time(imintime:imaxtime),double(sysvector.GPS_Alt(imintime:imaxtime)).*fconv_gpsalt,'color','red'); - hold off - legend('Barometric Altitude [m]','GPS Altitude [m]'); - else - legend('Barometric Altitude [m]'); - end - title(h.axes(5),'Altitude above MSL [m]'); - - % ************************************************************************ - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - % ************************************************************************ - figure(h.figures(4)); - %Attitude Estimate - plot(h.axes(6),time(imintime:imaxtime), [sysvector.ATT_Roll(imintime:imaxtime), sysvector.ATT_Pitch(imintime:imaxtime), sysvector.ATT_Yaw(imintime:imaxtime)] .*180./3.14159); - title(h.axes(6),'Estimated attitude [deg]'); - legend(h.axes(6),'roll','pitch','yaw'); - %Actuator Controls - plot(h.axes(7),time(imintime:imaxtime), [sysvector.ATTC_Roll(imintime:imaxtime), sysvector.ATTC_Pitch(imintime:imaxtime), sysvector.ATTC_Yaw(imintime:imaxtime), sysvector.ATTC_Thrust(imintime:imaxtime)]); - title(h.axes(7),'Actuator control [-]'); - legend(h.axes(7),'ATT CTRL Roll [-1..+1]','ATT CTRL Pitch [-1..+1]','ATT CTRL Yaw [-1..+1]','ATT CTRL Thrust [0..+1]'); - %Actuator Controls - plot(h.axes(8),time(imintime:imaxtime), [sysvector.OUT0_Out0(imintime:imaxtime), sysvector.OUT0_Out1(imintime:imaxtime), sysvector.OUT0_Out2(imintime:imaxtime), sysvector.OUT0_Out3(imintime:imaxtime), sysvector.OUT0_Out4(imintime:imaxtime), sysvector.OUT0_Out5(imintime:imaxtime), sysvector.OUT0_Out6(imintime:imaxtime), sysvector.OUT0_Out7(imintime:imaxtime)]); - title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); - legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); - set(h.axes(8), 'YLim',[800 2200]); - %Airspeeds - plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime)); - hold on - plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_TrueSpeed(imintime:imaxtime)); - hold off - %add GPS total airspeed here - title(h.axes(9),'Airspeed [m/s]'); - legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); - %calculate time differences and plot them - intervals = zeros(0,imaxtime - imintime); - for k = imintime+1:imaxtime - intervals(k) = time(k) - time(k-1); - end - plot(h.axes(10), time(imintime:imaxtime), intervals); - - %Set same timescale for all plots - for i=2:NrAxes - set(h.axes(i),'XLim',[mintime maxtime]); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% DRAWCURRENTAIRCRAFTSTATE(nested function) -% ************************************************************************ -function DrawCurrentAircraftState() - %find current data index - i=find(time>=CurTime,1,'first'); - - %********************************************************************** - % Current aircraft state label update - %********************************************************************** - acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.GPS_Lat(i))*fconv_gpslatlong),'°, ',... - 'lon=',num2str(double(sysvector.GPS_Lon(i))*fconv_gpslatlong),'°, ',... - 'alt=',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; - acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.IMU_MagX(i)),... - ', y=',num2str(sysvector.IMU_MagY(i)),... - ', z=',num2str(sysvector.IMU_MagZ(i)),']']; - acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.IMU_AccX(i)),... - ', y=',num2str(sysvector.IMU_AccY(i)),... - ', z=',num2str(sysvector.IMU_AccZ(i)),']']; - acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.IMU_GyroX(i)),... - ', y=',num2str(sysvector.IMU_GyroY(i)),... - ', z=',num2str(sysvector.IMU_GyroZ(i)),']']; - acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.SENS_BaroAlt(i)),'m, GPS: ',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; - acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.ATT_Roll(i).*180./3.14159),... - ', Pitch=',num2str(sysvector.ATT_Pitch(i).*180./3.14159),... - ', Yaw=',num2str(sysvector.ATT_Yaw(i).*180./3.14159),']']; - acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); - %for j=1:4 - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Roll(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Pitch(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Yaw(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Thrust(i)),',']; - %end - acstate{7,:}=[acstate{7,:},']']; - acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); - %for j=1:8 - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out0(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out1(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out2(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out3(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out4(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out5(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out6(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out7(i)),',']; - %end - acstate{8,:}=[acstate{8,:},']']; - acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.AIRS_IndSpeed(i)),', TAS: ',num2str(sysvector.AIRS_TrueSpeed(i)),']']; - - set(h.edits.AircraftState,'String',acstate); - - %********************************************************************** - % GPS Plot Update - %********************************************************************** - %Plot traveled path, and and time. - figure(h.figures(2)); - hold on; - if(CurTime>mintime+1) %the +1 is only a small bugfix - h.pathline=plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:i))*fconv_gpslatlong, ... - double(sysvector.GPS_Lon(imintime:i))*fconv_gpslatlong, ... - double(sysvector.GPS_Alt(imintime:i))*fconv_gpsalt,'b','LineWidth',2); - end; - hold off - %Plot current position - newpoint=[double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Alt(i))*fconv_gpsalt]; - if(numel(h.pathpoints)<=3) %empty path - h.pathpoints(1,1:3)=newpoint; - else %Not empty, append new point - h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; - end - axes(h.axes(1)); - line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); - - - % Plot current time (small label next to current gps position) - textdesc=strcat(' t=',num2str(time(i)),'s'); - if(isvalidhandle(h.markertext)) - delete(h.markertext); %delete old text - end - h.markertext=text(double(sysvector.GPS_Lat(i))*fconv_gpslatlong,double(sysvector.GPS_Lon(i))*fconv_gpslatlong,... - double(sysvector.GPS_Alt(i))*fconv_gpsalt,textdesc); - set(h.edits.CurTime,'String',CurTime); - - %********************************************************************** - % Plot the lines showing the current time in the 2-d plots - %********************************************************************** - for i=2:NrAxes - if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end - ylims=get(h.axes(i),'YLim'); - h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); - set(h.markerline(i),'parent',h.axes(i)); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% MINMAXTIME CALLBACK (nested function) -% ************************************************************************ -function minmaxtime_callback(hObj,event) %#ok - new_mintime=get(h.sliders.MinTime,'Value'); - new_maxtime=get(h.sliders.MaxTime,'Value'); - - %Safety checks: - bErr=false; - %1: mintime must be < maxtime - if((new_mintime>maxtime) || (new_maxtimeCurTime) - set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); - mintime=new_mintime; - CurTime=mintime; - bErr=true; - end - %3: MaxTime must be >CurTime - if(new_maxtime - %find current time - if(hObj==h.sliders.CurTime) - CurTime=get(h.sliders.CurTime,'Value'); - elseif (hObj==h.edits.CurTime) - temp=str2num(get(h.edits.CurTime,'String')); - if(tempmintime) - CurTime=temp; - else - %Error - set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); - end - else - %Error - set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); - end - - set(h.sliders.CurTime,'Value',CurTime); - set(h.edits.CurTime,'String',num2str(CurTime)); - - %Redraw time markers, but don't have to redraw the whole raw data - DrawCurrentAircraftState(); -end - -%% ************************************************************************ -% FINDMINMAXINDICES (nested function) -% ************************************************************************ -function [idxmin,idxmax] = FindMinMaxTimeIndices() - for i=1:size(sysvector.TIME_StartTime,1) - if time(i)>=mintime; idxmin=i; break; end - end - for i=1:size(sysvector.TIME_StartTime,1) - if maxtime==0; idxmax=size(sysvector.TIME_StartTime,1); break; end - if time(i)>=maxtime; idxmax=i; break; end - end - mintime=time(idxmin); - maxtime=time(idxmax); -end - -%% ************************************************************************ -% ISVALIDHANDLE (nested function) -% ************************************************************************ -function isvalid = isvalidhandle(handle) - if(exist(varname(handle))>0 && length(ishandle(handle))>0) - if(ishandle(handle)>0) - if(handle>0.0) - isvalid=true; - return; - end - end - end - isvalid=false; -end - -%% ************************************************************************ -% JUST SOME SMALL HELPER FUNCTIONS (nested function) -% ************************************************************************ -function out = varname(var) - out = inputname(1); -end - -%This is the end of the matlab file / the main function -end +% This Matlab Script can be used to import the binary logged values of the +% PX4FMU into data that can be plotted and analyzed. + +%% ************************************************************************ +% PX4LOG_PLOTSCRIPT: Main function +% ************************************************************************ +function PX4Log_Plotscript + +% Clear everything +clc +clear all +close all + +% ************************************************************************ +% SETTINGS +% ************************************************************************ + +% Set the path to your sysvector.bin file here +filePath = 'log001.bin'; + +% Set the minimum and maximum times to plot here [in seconds] +mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] +maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] + +%Determine which data to plot. Not completely implemented yet. +bDisplayGPS=true; + +%conversion factors +fconv_gpsalt=1; %[mm] to [m] +fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg] +fconv_timestamp=1E-6; % [microseconds] to [seconds] + +% ************************************************************************ +% Import the PX4 logs +% ************************************************************************ +ImportPX4LogData(); + +%Translate min and max plot times to indices +time=double(sysvector.TIME_StartTime) .*fconv_timestamp; +mintime_log=time(1); %The minimum time/timestamp found in the log +maxtime_log=time(end); %The maximum time/timestamp found in the log +CurTime=mintime_log; %The current time at which to draw the aircraft position + +[imintime,imaxtime]=FindMinMaxTimeIndices(); + +% ************************************************************************ +% PLOT & GUI SETUP +% ************************************************************************ +NrFigures=5; +NrAxes=10; +h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively +h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively +h.pathpoints=[]; % Temporary initiliazation of path points + +% Setup the GUI to control the plots +InitControlGUI(); +% Setup the plotting-GUI (figures, axes) itself. +InitPlotGUI(); + +% ************************************************************************ +% DRAW EVERYTHING +% ************************************************************************ +DrawRawData(); +DrawCurrentAircraftState(); + +%% ************************************************************************ +% *** END OF MAIN SCRIPT *** +% NESTED FUNCTION DEFINTIONS FROM HERE ON +% ************************************************************************ + + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +function ImportPX4LogData() + + % ************************************************************************ + % RETRIEVE SYSTEM VECTOR + % ************************************************************************* + % //All measurements in NED frame + + % Convert to CSV + %arg1 = 'log-fx61-20130721-2.bin'; + arg1 = filePath; + delim = ','; + time_field = 'TIME'; + data_file = 'data.csv'; + csv_null = ''; + + if not(exist(data_file, 'file')) + s = system( sprintf('python sdlog2_dump.py "%s" -f "%s" -t"%s" -d"%s" -n"%s"', arg1, data_file, time_field, delim, csv_null) ); + end + + if exist(data_file, 'file') + + %data = csvread(data_file); + sysvector = tdfread(data_file, ','); + + % shot the flight time + time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); + time_s = uint64(time_us*1e-6); + time_m = uint64(time_s/60); + time_s = time_s - time_m * 60; + + disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); + + disp(['logfile conversion finished.' char(10)]); + else + disp(['file: ' data_file ' does not exist' char(10)]); + end +end + +%% ************************************************************************ +% INITCONTROLGUI (nested function) +% ************************************************************************ +%Setup central control GUI components to control current time where data is shown +function InitControlGUI() + %********************************************************************** + % GUI size definitions + %********************************************************************** + dxy=5; %margins + %Panel: Plotctrl + dlabels=120; + dsliders=200; + dedits=80; + hslider=20; + + hpanel1=40; %panel1 + hpanel2=220;%panel2 + hpanel3=3*hslider+4*dxy+3*dxy;%panel3. + + width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width + height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height + + %********************************************************************** + % Create GUI + %********************************************************************** + h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); + h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); + h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); + h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); + + %%Control GUI-elements + %Slider: Current time + h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... + 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); + temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); + set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); + h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... + 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); + + %Slider: MaxTime + h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %Slider: MinTime + h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %%Current data/state GUI-elements (Multiline-edit-box) + h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... + 'HorizontalAlignment','left','parent',h.aircraftstatepanel); + + h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... + 'HorizontalAlignment','left','parent',h.guistatepanel); + +end + +%% ************************************************************************ +% INITPLOTGUI (nested function) +% ************************************************************************ +function InitPlotGUI() + + % Setup handles to lines and text + h.markertext=[]; + templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array + h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively + h.markerline(1:NrAxes)=0.0; + + % Setup all other figures and axes for plotting + % PLOT WINDOW 1: GPS POSITION + h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); + h.axes(1)=axes(); + set(h.axes(1),'Parent',h.figures(2)); + + % PLOT WINDOW 2: IMU, baro altitude + h.figures(3)=figure('Name', 'IMU / Baro Altitude'); + h.axes(2)=subplot(4,1,1); + h.axes(3)=subplot(4,1,2); + h.axes(4)=subplot(4,1,3); + h.axes(5)=subplot(4,1,4); + set(h.axes(2:5),'Parent',h.figures(3)); + + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); + h.axes(6)=subplot(4,1,1); + h.axes(7)=subplot(4,1,2); + h.axes(8)=subplot(4,1,3); + h.axes(9)=subplot(4,1,4); + set(h.axes(6:9),'Parent',h.figures(4)); + + % PLOT WINDOW 4: LOG STATS + h.figures(5) = figure('Name', 'Log Statistics'); + h.axes(10)=subplot(1,1,1); + set(h.axes(10:10),'Parent',h.figures(5)); + +end + +%% ************************************************************************ +% DRAWRAWDATA (nested function) +% ************************************************************************ +%Draws the raw data from the sysvector, but does not add any +%marker-lines or so +function DrawRawData() + % ************************************************************************ + % PLOT WINDOW 1: GPS POSITION & GUI + % ************************************************************************ + figure(h.figures(2)); + % Only plot GPS data if available + if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS) + %Draw data + plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:imaxtime))*fconv_gpsalt,'r.'); + title(h.axes(1),'GPS Position Data(if available)'); + xlabel(h.axes(1),'Latitude [deg]'); + ylabel(h.axes(1),'Longitude [deg]'); + zlabel(h.axes(1),'Altitude above MSL [m]'); + grid on + + %Reset path + h.pathpoints=0; + end + + % ************************************************************************ + % PLOT WINDOW 2: IMU, baro altitude + % ************************************************************************ + figure(h.figures(3)); + plot(h.axes(2),time(imintime:imaxtime),[sysvector.IMU_MagX(imintime:imaxtime), sysvector.IMU_MagY(imintime:imaxtime), sysvector.IMU_MagZ(imintime:imaxtime)]); + title(h.axes(2),'Magnetometers [Gauss]'); + legend(h.axes(2),'x','y','z'); + plot(h.axes(3),time(imintime:imaxtime),[sysvector.IMU_AccX(imintime:imaxtime), sysvector.IMU_AccY(imintime:imaxtime), sysvector.IMU_AccZ(imintime:imaxtime)]); + title(h.axes(3),'Accelerometers [m/s²]'); + legend(h.axes(3),'x','y','z'); + plot(h.axes(4),time(imintime:imaxtime),[sysvector.IMU_GyroX(imintime:imaxtime), sysvector.IMU_GyroY(imintime:imaxtime), sysvector.IMU_GyroZ(imintime:imaxtime)]); + title(h.axes(4),'Gyroscopes [rad/s]'); + legend(h.axes(4),'x','y','z'); + plot(h.axes(5),time(imintime:imaxtime),sysvector.SENS_BaroAlt(imintime:imaxtime),'color','blue'); + if(bDisplayGPS) + hold on; + plot(h.axes(5),time(imintime:imaxtime),double(sysvector.GPS_Alt(imintime:imaxtime)).*fconv_gpsalt,'color','red'); + hold off + legend('Barometric Altitude [m]','GPS Altitude [m]'); + else + legend('Barometric Altitude [m]'); + end + title(h.axes(5),'Altitude above MSL [m]'); + + % ************************************************************************ + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + % ************************************************************************ + figure(h.figures(4)); + %Attitude Estimate + plot(h.axes(6),time(imintime:imaxtime), [sysvector.ATT_Roll(imintime:imaxtime), sysvector.ATT_Pitch(imintime:imaxtime), sysvector.ATT_Yaw(imintime:imaxtime)] .*180./3.14159); + title(h.axes(6),'Estimated attitude [deg]'); + legend(h.axes(6),'roll','pitch','yaw'); + %Actuator Controls + plot(h.axes(7),time(imintime:imaxtime), [sysvector.ATTC_Roll(imintime:imaxtime), sysvector.ATTC_Pitch(imintime:imaxtime), sysvector.ATTC_Yaw(imintime:imaxtime), sysvector.ATTC_Thrust(imintime:imaxtime)]); + title(h.axes(7),'Actuator control [-]'); + legend(h.axes(7),'ATT CTRL Roll [-1..+1]','ATT CTRL Pitch [-1..+1]','ATT CTRL Yaw [-1..+1]','ATT CTRL Thrust [0..+1]'); + %Actuator Controls + plot(h.axes(8),time(imintime:imaxtime), [sysvector.OUT0_Out0(imintime:imaxtime), sysvector.OUT0_Out1(imintime:imaxtime), sysvector.OUT0_Out2(imintime:imaxtime), sysvector.OUT0_Out3(imintime:imaxtime), sysvector.OUT0_Out4(imintime:imaxtime), sysvector.OUT0_Out5(imintime:imaxtime), sysvector.OUT0_Out6(imintime:imaxtime), sysvector.OUT0_Out7(imintime:imaxtime)]); + title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); + legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); + set(h.axes(8), 'YLim',[800 2200]); + %Airspeeds + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime)); + hold on + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_TrueSpeed(imintime:imaxtime)); + hold off + %add GPS total airspeed here + title(h.axes(9),'Airspeed [m/s]'); + legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); + %calculate time differences and plot them + intervals = zeros(0,imaxtime - imintime); + for k = imintime+1:imaxtime + intervals(k) = time(k) - time(k-1); + end + plot(h.axes(10), time(imintime:imaxtime), intervals); + + %Set same timescale for all plots + for i=2:NrAxes + set(h.axes(i),'XLim',[mintime maxtime]); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% DRAWCURRENTAIRCRAFTSTATE(nested function) +% ************************************************************************ +function DrawCurrentAircraftState() + %find current data index + i=find(time>=CurTime,1,'first'); + + %********************************************************************** + % Current aircraft state label update + %********************************************************************** + acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.GPS_Lat(i))*fconv_gpslatlong),'°, ',... + 'lon=',num2str(double(sysvector.GPS_Lon(i))*fconv_gpslatlong),'°, ',... + 'alt=',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.IMU_MagX(i)),... + ', y=',num2str(sysvector.IMU_MagY(i)),... + ', z=',num2str(sysvector.IMU_MagZ(i)),']']; + acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.IMU_AccX(i)),... + ', y=',num2str(sysvector.IMU_AccY(i)),... + ', z=',num2str(sysvector.IMU_AccZ(i)),']']; + acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.IMU_GyroX(i)),... + ', y=',num2str(sysvector.IMU_GyroY(i)),... + ', z=',num2str(sysvector.IMU_GyroZ(i)),']']; + acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.SENS_BaroAlt(i)),'m, GPS: ',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.ATT_Roll(i).*180./3.14159),... + ', Pitch=',num2str(sysvector.ATT_Pitch(i).*180./3.14159),... + ', Yaw=',num2str(sysvector.ATT_Yaw(i).*180./3.14159),']']; + acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); + %for j=1:4 + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Roll(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Pitch(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Yaw(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Thrust(i)),',']; + %end + acstate{7,:}=[acstate{7,:},']']; + acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); + %for j=1:8 + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out0(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out1(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out2(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out3(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out4(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out5(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out6(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out7(i)),',']; + %end + acstate{8,:}=[acstate{8,:},']']; + acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.AIRS_IndSpeed(i)),', TAS: ',num2str(sysvector.AIRS_TrueSpeed(i)),']']; + + set(h.edits.AircraftState,'String',acstate); + + %********************************************************************** + % GPS Plot Update + %********************************************************************** + %Plot traveled path, and and time. + figure(h.figures(2)); + hold on; + if(CurTime>mintime+1) %the +1 is only a small bugfix + h.pathline=plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:i))*fconv_gpsalt,'b','LineWidth',2); + end; + hold off + %Plot current position + newpoint=[double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Alt(i))*fconv_gpsalt]; + if(numel(h.pathpoints)<=3) %empty path + h.pathpoints(1,1:3)=newpoint; + else %Not empty, append new point + h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; + end + axes(h.axes(1)); + line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); + + + % Plot current time (small label next to current gps position) + textdesc=strcat(' t=',num2str(time(i)),'s'); + if(isvalidhandle(h.markertext)) + delete(h.markertext); %delete old text + end + h.markertext=text(double(sysvector.GPS_Lat(i))*fconv_gpslatlong,double(sysvector.GPS_Lon(i))*fconv_gpslatlong,... + double(sysvector.GPS_Alt(i))*fconv_gpsalt,textdesc); + set(h.edits.CurTime,'String',CurTime); + + %********************************************************************** + % Plot the lines showing the current time in the 2-d plots + %********************************************************************** + for i=2:NrAxes + if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end + ylims=get(h.axes(i),'YLim'); + h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); + set(h.markerline(i),'parent',h.axes(i)); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% MINMAXTIME CALLBACK (nested function) +% ************************************************************************ +function minmaxtime_callback(hObj,event) %#ok + new_mintime=get(h.sliders.MinTime,'Value'); + new_maxtime=get(h.sliders.MaxTime,'Value'); + + %Safety checks: + bErr=false; + %1: mintime must be < maxtime + if((new_mintime>maxtime) || (new_maxtimeCurTime) + set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); + mintime=new_mintime; + CurTime=mintime; + bErr=true; + end + %3: MaxTime must be >CurTime + if(new_maxtime + %find current time + if(hObj==h.sliders.CurTime) + CurTime=get(h.sliders.CurTime,'Value'); + elseif (hObj==h.edits.CurTime) + temp=str2num(get(h.edits.CurTime,'String')); + if(tempmintime) + CurTime=temp; + else + %Error + set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); + end + else + %Error + set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); + end + + set(h.sliders.CurTime,'Value',CurTime); + set(h.edits.CurTime,'String',num2str(CurTime)); + + %Redraw time markers, but don't have to redraw the whole raw data + DrawCurrentAircraftState(); +end + +%% ************************************************************************ +% FINDMINMAXINDICES (nested function) +% ************************************************************************ +function [idxmin,idxmax] = FindMinMaxTimeIndices() + for i=1:size(sysvector.TIME_StartTime,1) + if time(i)>=mintime; idxmin=i; break; end + end + for i=1:size(sysvector.TIME_StartTime,1) + if maxtime==0; idxmax=size(sysvector.TIME_StartTime,1); break; end + if time(i)>=maxtime; idxmax=i; break; end + end + mintime=time(idxmin); + maxtime=time(idxmax); +end + +%% ************************************************************************ +% ISVALIDHANDLE (nested function) +% ************************************************************************ +function isvalid = isvalidhandle(handle) + if(exist(varname(handle))>0 && length(ishandle(handle))>0) + if(ishandle(handle)>0) + if(handle>0.0) + isvalid=true; + return; + end + end + end + isvalid=false; +end + +%% ************************************************************************ +% JUST SOME SMALL HELPER FUNCTIONS (nested function) +% ************************************************************************ +function out = varname(var) + out = inputname(1); +end + +%This is the end of the matlab file / the main function +end diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2/sdlog2_dump.py similarity index 100% rename from Tools/sdlog2_dump.py rename to Tools/sdlog2/sdlog2_dump.py From a8b3381ca9675890b0d36e98a4453ac18d19df3e Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 17 Feb 2014 21:29:14 +0100 Subject: [PATCH 19/76] BL-Ctrl 3.0 fix --- src/drivers/mkblctrl/mkblctrl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index ec5f77d747..705e98eea4 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -705,7 +705,7 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C) Motor[i].State |= MOTOR_STATE_PRESENT_MASK; // set present bit; foundMotorCount++; - if (Motor[i].MaxPWM == 250) { + if ((Motor[i].MaxPWM & 252) == 248) { Motor[i].Version = BLCTRL_NEW; } else { From 4cfaf928e12ac8927b3980506f31c05a1ab899ce Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Feb 2014 16:11:46 +0400 Subject: [PATCH 20/76] px4io: bug in failsafe fixed --- src/modules/px4iofirmware/mixer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index f39fcf7ec6..6a44294619 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -179,7 +179,7 @@ mixer_tick(void) ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) /* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ) /* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) - /* or failsafe was set manually */ || (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) + /* or failsafe was set manually */ || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) ) ); From 4b519e4d5daee4da8e619414d4b1cd697198b6a3 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 18 Feb 2014 14:04:11 +0100 Subject: [PATCH 21/76] Navigator: Get rid of warnings first --- src/modules/navigator/navigator_main.cpp | 46 ++++++++++++------------ 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 577c767a86..f59663ca00 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -154,17 +154,16 @@ private: int _capabilities_sub; /**< notification of vehicle capabilities updates */ int _control_mode_sub; /**< vehicle control mode subscription */ - orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */ + orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */ orb_advert_t _mission_result_pub; /**< publish mission result topic */ struct vehicle_status_s _vstatus; /**< vehicle status */ - struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */ + struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */ struct vehicle_global_position_s _global_pos; /**< global vehicle position */ struct home_position_s _home_pos; /**< home position for RTL */ - struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */ + struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */ struct mission_result_s _mission_result; /**< mission result for commander/mavlink */ - struct mission_item_s _mission_item; /**< current mission item */ - bool _mission_item_valid; /**< current mission item valid */ + struct mission_item_s _mission_item; /**< current mission item */ perf_counter_t _loop_perf; /**< loop performance counter */ @@ -178,21 +177,22 @@ private: class Mission _mission; - bool _global_pos_valid; /**< track changes of global_position.global_valid flag */ - bool _reset_loiter_pos; /**< if true then loiter position should be set to current position */ + bool _mission_item_valid; /**< current mission item valid */ + bool _global_pos_valid; /**< track changes of global_position.global_valid flag */ + bool _reset_loiter_pos; /**< if true then loiter position should be set to current position */ bool _waypoint_position_reached; bool _waypoint_yaw_reached; uint64_t _time_first_inside_orbit; - bool _need_takeoff; /**< if need to perform vertical takeoff before going to waypoint (only for MISSION mode and VTOL vehicles) */ - bool _do_takeoff; /**< vertical takeoff state, current mission item is generated by navigator (only for MISSION mode and VTOL vehicles) */ + bool _need_takeoff; /**< if need to perform vertical takeoff before going to waypoint (only for MISSION mode and VTOL vehicles) */ + bool _do_takeoff; /**< vertical takeoff state, current mission item is generated by navigator (only for MISSION mode and VTOL vehicles) */ MissionFeasibilityChecker missionFeasiblityChecker; - uint64_t _set_nav_state_timestamp; /**< timestamp of last handled navigation state request */ + uint64_t _set_nav_state_timestamp; /**< timestamp of last handled navigation state request */ bool _pos_sp_triplet_updated; - char *nav_states_str[NAV_STATE_MAX]; + const char *nav_states_str[NAV_STATE_MAX]; struct { float min_altitude; @@ -382,11 +382,11 @@ Navigator::Navigator() : _global_pos_sub(-1), _home_pos_sub(-1), _vstatus_sub(-1), - _control_mode_sub(-1), _params_sub(-1), _offboard_mission_sub(-1), _onboard_mission_sub(-1), _capabilities_sub(-1), + _control_mode_sub(-1), /* publications */ _pos_sp_triplet_pub(-1), @@ -395,22 +395,22 @@ Navigator::Navigator() : /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "navigator")), -/* states */ - _rtl_state(RTL_STATE_NONE), + _geofence_violation_warning_sent(false), _fence_valid(false), _inside_fence(true), _mission(), + _mission_item_valid(false), _global_pos_valid(false), _reset_loiter_pos(true), _waypoint_position_reached(false), _waypoint_yaw_reached(false), _time_first_inside_orbit(0), - _set_nav_state_timestamp(0), - _mission_item_valid(false), _need_takeoff(true), _do_takeoff(false), + _set_nav_state_timestamp(0), _pos_sp_triplet_updated(false), - _geofence_violation_warning_sent(false) +/* states */ + _rtl_state(RTL_STATE_NONE) { _parameter_handles.min_altitude = param_find("NAV_MIN_ALT"); _parameter_handles.acceptance_radius = param_find("NAV_ACCEPT_RAD"); @@ -1162,7 +1162,7 @@ Navigator::set_mission_item() } if (_do_takeoff) { - mavlink_log_info(_mavlink_fd, "[navigator] takeoff to %.1fm above home", _pos_sp_triplet.current.alt - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "[navigator] takeoff to %.1fm above home", (double)(_pos_sp_triplet.current.alt - _home_pos.alt)); } else { if (onboard) { @@ -1318,7 +1318,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm above home", climb_alt - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm above home", (double)(climb_alt - _home_pos.alt)); break; } @@ -1344,7 +1344,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: return at %.1fm above home", _mission_item.altitude - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "[navigator] RTL: return at %.1fm above home", (double)(_mission_item.altitude - _home_pos.alt)); break; } @@ -1362,7 +1362,7 @@ Navigator::set_rtl_item() _mission_item.loiter_direction = 1; _mission_item.nav_cmd = NAV_CMD_WAYPOINT; _mission_item.acceptance_radius = _parameters.acceptance_radius; - _mission_item.time_inside = _parameters.rtl_land_delay < 0.0 ? 0.0f : _parameters.rtl_land_delay; + _mission_item.time_inside = _parameters.rtl_land_delay < 0.0f ? 0.0f : _parameters.rtl_land_delay; _mission_item.pitch_min = 0.0f; _mission_item.autocontinue = _parameters.rtl_land_delay > -0.001f; _mission_item.origin = ORIGIN_ONBOARD; @@ -1371,7 +1371,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm above home", _mission_item.altitude - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm above home", (double)(_mission_item.altitude - _home_pos.alt)); break; } @@ -1525,7 +1525,7 @@ Navigator::check_mission_item_reached() _time_first_inside_orbit = now; if (_mission_item.time_inside > 0.01f) { - mavlink_log_info(_mavlink_fd, "[navigator] waypoint reached, wait for %.1fs", _mission_item.time_inside); + mavlink_log_info(_mavlink_fd, "[navigator] waypoint reached, wait for %.1fs", (double)_mission_item.time_inside); } } From 3eaa892ee42f7de84698d46ef8cf3b29b96a2b34 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 18 Feb 2014 14:35:41 +0100 Subject: [PATCH 22/76] fw_pos_control_l1: indentation only --- .../fw_pos_control_l1_main.cpp | 32 +++++++++---------- 1 file changed, 16 insertions(+), 16 deletions(-) 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 index 45fdaa355e..10aa890885 100644 --- 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 @@ -130,23 +130,23 @@ private: 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 _control_mode_sub; /**< vehicle status subscription */ int _params_sub; /**< notification of parameter updates */ int _manual_control_sub; /**< notification of manual control updates */ - int _sensor_combined_sub; /**< for body frame accelerations */ + int _sensor_combined_sub; /**< for body frame accelerations */ orb_advert_t _attitude_sp_pub; /**< attitude setpoint */ orb_advert_t _nav_capabilities_pub; /**< navigation capabilities publication */ - struct vehicle_attitude_s _att; /**< vehicle attitude */ - struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */ - struct navigation_capabilities_s _nav_capabilities; /**< navigation capabilities */ - 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 position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */ - struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */ + struct vehicle_attitude_s _att; /**< vehicle attitude */ + struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */ + struct navigation_capabilities_s _nav_capabilities; /**< navigation capabilities */ + 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 position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */ + struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */ perf_counter_t _loop_perf; /**< loop performance counter */ @@ -192,7 +192,7 @@ private: 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::Matrix<3, 3> _R_nb; ///< current attitude + math::Matrix<3, 3> _R_nb; ///< current attitude ECL_L1_Pos_Controller _l1_control; TECS _tecs; @@ -406,8 +406,8 @@ FixedwingPositionControl::FixedwingPositionControl() : airspeed_s _airspeed = {0}; vehicle_control_mode_s _control_mode = {0}; vehicle_global_position_s _global_pos = {0}; - position_setpoint_triplet_s _pos_sp_triplet = {0}; - sensor_combined_s _sensor_combined = {0}; + position_setpoint_triplet_s _pos_sp_triplet = {0}; + sensor_combined_s _sensor_combined = {0}; @@ -587,8 +587,8 @@ FixedwingPositionControl::vehicle_control_mode_poll() 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_lat = _global_pos.lat / 1e7d; + _launch_lon = _global_pos.lon / 1e7d; _launch_alt = _global_pos.alt; _launch_valid = true; } From 83f66e45999c7db8734534ba1cfb9f9e023f47a7 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 18 Feb 2014 14:40:11 +0100 Subject: [PATCH 23/76] fw_pos_control_l1: use double everywhere for lat and lon --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) 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 index 10aa890885..c1aa8d39c8 100644 --- 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 @@ -154,13 +154,13 @@ private: /** manual control states */ float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */ - float _loiter_hold_lat; - float _loiter_hold_lon; + double _loiter_hold_lat; + double _loiter_hold_lon; float _loiter_hold_alt; bool _loiter_hold; - float _launch_lat; - float _launch_lon; + double _launch_lat; + double _launch_lon; float _launch_alt; bool _launch_valid; @@ -587,8 +587,8 @@ FixedwingPositionControl::vehicle_control_mode_poll() orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); if (!was_armed && _control_mode.flag_armed) { - _launch_lat = _global_pos.lat / 1e7d; - _launch_lon = _global_pos.lon / 1e7d; + _launch_lat = _global_pos.lat; + _launch_lon = _global_pos.lon; _launch_alt = _global_pos.alt; _launch_valid = true; } From a43c7c488eaba5022a18f05e590059cad6f580da Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Feb 2014 18:54:58 +0400 Subject: [PATCH 24/76] navigator: "reached" flags reset fixed --- src/modules/navigator/navigator_main.cpp | 39 +++++++++++++++++------- 1 file changed, 28 insertions(+), 11 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 0ed12d1062..af1b9aac02 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -321,6 +321,11 @@ private: */ bool onboard_mission_available(unsigned relative_index); + /** + * Reset all "reached" flags. + */ + void reset_reached(); + /** * Check if current mission item has been reached. */ @@ -855,9 +860,6 @@ Navigator::task_main() if (myState != prevState) { mavlink_log_info(_mavlink_fd, "[navigator] nav state: %s", nav_states_str[myState]); prevState = myState; - - /* reset time counter on state changes */ - _time_first_inside_orbit = 0; } perf_end(_loop_perf); @@ -1009,6 +1011,8 @@ StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { void Navigator::start_none() { + reset_reached(); + _pos_sp_triplet.previous.valid = false; _pos_sp_triplet.current.valid = false; _pos_sp_triplet.next.valid = false; @@ -1024,6 +1028,8 @@ Navigator::start_none() void Navigator::start_ready() { + reset_reached(); + _pos_sp_triplet.previous.valid = false; _pos_sp_triplet.current.valid = true; _pos_sp_triplet.next.valid = false; @@ -1046,6 +1052,8 @@ Navigator::start_ready() void Navigator::start_loiter() { + reset_reached(); + _do_takeoff = false; /* set loiter position if needed */ @@ -1091,6 +1099,8 @@ Navigator::start_mission() void Navigator::set_mission_item() { + reset_reached(); + /* copy current mission to previous item */ memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s)); @@ -1104,9 +1114,6 @@ Navigator::set_mission_item() ret = _mission.get_current_mission_item(&_mission_item, &onboard, &index); if (ret == OK) { - /* reset time counter for new item */ - _time_first_inside_orbit = 0; - _mission_item_valid = true; position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item); @@ -1224,6 +1231,8 @@ Navigator::start_rtl() void Navigator::start_land() { + reset_reached(); + /* this state can be requested by commander even if no global position available, * in his case controller must perform landing without position control */ _do_takeoff = false; @@ -1255,6 +1264,8 @@ Navigator::start_land() void Navigator::start_land_home() { + reset_reached(); + /* land to home position, should be called when hovering above home, from RTL state */ _do_takeoff = false; _reset_loiter_pos = true; @@ -1285,8 +1296,7 @@ Navigator::start_land_home() void Navigator::set_rtl_item() { - /*reset time counter for new RTL item */ - _time_first_inside_orbit = 0; + reset_reached(); switch (_rtl_state) { case RTL_STATE_CLIMB: { @@ -1550,9 +1560,7 @@ Navigator::check_mission_item_reached() /* check if the MAV was long enough inside the waypoint orbit */ if ((now - _time_first_inside_orbit >= (uint64_t)_mission_item.time_inside * 1e6) || _mission_item.nav_cmd == NAV_CMD_TAKEOFF) { - _time_first_inside_orbit = 0; - _waypoint_yaw_reached = false; - _waypoint_position_reached = false; + reset_reached(); return true; } } @@ -1561,6 +1569,15 @@ Navigator::check_mission_item_reached() } +void +Navigator::reset_reached() +{ + _time_first_inside_orbit = 0; + _waypoint_position_reached = false; + _waypoint_yaw_reached = false; + +} + void Navigator::on_mission_item_reached() { From 7d8f08ad9a733111a9d8b1512a85592a2fb9b045 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Feb 2014 19:05:32 +0400 Subject: [PATCH 25/76] navigator: check if yaw reached only when position reached --- src/modules/navigator/navigator_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index af1b9aac02..4cd60d8d89 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1533,7 +1533,7 @@ Navigator::check_mission_item_reached() } } - if (!_waypoint_yaw_reached) { + if (_waypoint_position_reached && !_waypoint_yaw_reached) { if (_vstatus.is_rotary_wing && !_do_takeoff && isfinite(_mission_item.yaw)) { /* check yaw if defined only for rotary wing except takeoff */ float yaw_err = _wrap_pi(_mission_item.yaw - _global_pos.yaw); From 84d9e3479f3d2bb29b22906be0dfe65d73b5dd0f Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Feb 2014 23:42:02 +0400 Subject: [PATCH 26/76] mc_pos_control: unused variables removed --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index b06655385a..b4bac53d66 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -730,7 +730,6 @@ MulticopterPositionControl::task_main() } else { /* run position & altitude controllers, calculate velocity setpoint */ math::Vector<3> pos_err; - float err_x, err_y; get_vector_to_next_waypoint_fast(_global_pos.lat, _global_pos.lon, _lat_sp, _lon_sp, &pos_err.data[0], &pos_err.data[1]); pos_err(2) = -(_alt_sp - alt); From 79d2e5de6cf00186359e5b436c602055e4110249 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 19 Feb 2014 10:48:31 +0100 Subject: [PATCH 27/76] TECS: use constant from geo --- src/lib/ecl/ecl.h | 3 +-- src/lib/external_lgpl/tecs/tecs.cpp | 5 +---- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/src/lib/ecl/ecl.h b/src/lib/ecl/ecl.h index e0f207696a..aa3c5000a4 100644 --- a/src/lib/ecl/ecl.h +++ b/src/lib/ecl/ecl.h @@ -38,7 +38,6 @@ */ #include -#include #define ecl_absolute_time hrt_absolute_time -#define ecl_elapsed_time hrt_elapsed_time \ No newline at end of file +#define ecl_elapsed_time hrt_elapsed_time diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp index 0f28bccadd..3730b19204 100644 --- a/src/lib/external_lgpl/tecs/tecs.cpp +++ b/src/lib/external_lgpl/tecs/tecs.cpp @@ -3,13 +3,10 @@ #include "tecs.h" #include #include +#include using namespace math; -#ifndef CONSTANTS_ONE_G -#define CONSTANTS_ONE_G GRAVITY -#endif - /** * @file tecs.cpp * From 84df8ee78d28c51fc0f6272771d3b7c12b281cfe Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 19 Feb 2014 10:48:46 +0100 Subject: [PATCH 28/76] TECS: warning fixes --- src/lib/external_lgpl/tecs/tecs.h | 27 +++++++++++++-------------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h index d1ebacda16..5cafb1c791 100644 --- a/src/lib/external_lgpl/tecs/tecs.h +++ b/src/lib/external_lgpl/tecs/tecs.h @@ -28,16 +28,7 @@ class __EXPORT TECS { public: TECS() : - - _airspeed_enabled(false), - _throttle_slewrate(0.0f), - _climbOutDem(false), - _hgt_dem_prev(0.0f), - _hgt_dem_adj_last(0.0f), - _hgt_dem_in_old(0.0f), - _TAS_dem_last(0.0f), - _TAS_dem_adj(0.0f), - _TAS_dem(0.0f), + _pitch_dem(0.0f), _integ1_state(0.0f), _integ2_state(0.0f), _integ3_state(0.0f), @@ -45,8 +36,16 @@ public: _integ5_state(0.0f), _integ6_state(0.0f), _integ7_state(0.0f), - _pitch_dem(0.0f), _last_pitch_dem(0.0f), + _vel_dot(0.0f), + _TAS_dem(0.0f), + _TAS_dem_last(0.0f), + _hgt_dem_in_old(0.0f), + _hgt_dem_adj_last(0.0f), + _hgt_dem_prev(0.0f), + _TAS_dem_adj(0.0f), + _STEdotErrLast(0.0f), + _climbOutDem(false), _SPE_dem(0.0f), _SKE_dem(0.0f), _SPEdot_dem(0.0f), @@ -55,9 +54,9 @@ public: _SKE_est(0.0f), _SPEdot(0.0f), _SKEdot(0.0f), - _vel_dot(0.0f), - _STEdotErrLast(0.0f) { - + _airspeed_enabled(false), + _throttle_slewrate(0.0f) + { } bool airspeed_sensor_enabled() { From 18f71e6bc41e9823f8c82c49c03ee8c7261b8053 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 19 Feb 2014 10:49:03 +0100 Subject: [PATCH 29/76] fw_pos_control_l1: warning fixes --- .../fw_pos_control_l1_main.cpp | 55 ++++++++++--------- 1 file changed, 28 insertions(+), 27 deletions(-) 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 index c1aa8d39c8..62c69d3ebe 100644 --- 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 @@ -362,6 +362,7 @@ FixedwingPositionControl *g_control; FixedwingPositionControl::FixedwingPositionControl() : + _mavlink_fd(-1), _task_should_exit(false), _control_task(-1), @@ -380,36 +381,34 @@ FixedwingPositionControl::FixedwingPositionControl() : /* 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), land_noreturn_horizontal(false), land_noreturn_vertical(false), land_stayonground(false), land_motor_lim(false), land_onslope(false), - flare_curve_alt_last(0.0f), - _mavlink_fd(-1), - launchDetector(), launch_detected(false), - usePreTakeoffThrust(false) + usePreTakeoffThrust(false), + flare_curve_alt_last(0.0f), + launchDetector(), + _airspeed_error(0.0f), + _airspeed_valid(false), + _groundspeed_undershoot(0.0f), + _global_pos_valid(false) { /* safely initialize structs */ - vehicle_attitude_s _att = {0}; - vehicle_attitude_setpoint_s _att_sp = {0}; - navigation_capabilities_s _nav_capabilities = {0}; - manual_control_setpoint_s _manual = {0}; - airspeed_s _airspeed = {0}; - vehicle_control_mode_s _control_mode = {0}; - vehicle_global_position_s _global_pos = {0}; - position_setpoint_triplet_s _pos_sp_triplet = {0}; - sensor_combined_s _sensor_combined = {0}; - - + memset(&_att, 0, sizeof(vehicle_attitude_s)); + memset(&_att_sp, 0, sizeof(vehicle_attitude_setpoint_s)); + memset(&_nav_capabilities, 0, sizeof(navigation_capabilities_s)); + memset(&_manual, 0, sizeof(manual_control_setpoint_s)); + memset(&_airspeed, 0, sizeof(airspeed_s)); + memset(&_control_mode, 0, sizeof(vehicle_control_mode_s)); + memset(&_global_pos, 0, sizeof(vehicle_global_position_s)); + memset(&_pos_sp_triplet, 0, sizeof(position_setpoint_triplet_s)); + memset(&_sensor_combined, 0, sizeof(sensor_combined_s)); _nav_capabilities.turn_distance = 0.0f; @@ -916,7 +915,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float flare_curve_alt = landingslope.getFlareCurveAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt); /* avoid climbout */ - if (flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical || land_stayonground) + if ((flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical) || land_stayonground) { flare_curve_alt = pos_sp_triplet.current.alt; land_stayonground = true; @@ -1074,13 +1073,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi _seatbelt_hold_heading = _att.yaw + _manual.yaw; } - /* climb out control */ - bool climb_out = false; + //XXX not used - /* user wants to climb out */ - if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) { - climb_out = true; - } + /* climb out control */ +// bool climb_out = false; +// +// /* user wants to climb out */ +// if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) { +// climb_out = true; +// } /* if in seatbelt mode, set airspeed based on manual control */ @@ -1287,7 +1288,7 @@ FixedwingPositionControl::task_main() float turn_distance = _l1_control.switch_distance(100.0f); /* lazily publish navigation capabilities */ - if (turn_distance != _nav_capabilities.turn_distance && turn_distance > 0) { + if (fabsf(turn_distance - _nav_capabilities.turn_distance) > FLT_EPSILON && turn_distance > 0) { /* set new turn distance */ _nav_capabilities.turn_distance = turn_distance; From 6480c6a2cee7a237f9310f6986567e91c54c1247 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 19 Feb 2014 21:48:54 +0100 Subject: [PATCH 30/76] fw autoland: remove confusing slopelength parameter --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 6 +----- src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c | 7 ------- 2 files changed, 1 insertion(+), 12 deletions(-) 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 index 45fdaa355e..020d1c119e 100644 --- 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 @@ -233,7 +233,6 @@ private: float speedrate_p; float land_slope_angle; - float land_slope_length; float land_H1_virt; float land_flare_alt_relative; float land_thrust_lim_alt_relative; @@ -278,7 +277,6 @@ private: param_t speedrate_p; param_t land_slope_angle; - param_t land_slope_length; param_t land_H1_virt; param_t land_flare_alt_relative; param_t land_thrust_lim_alt_relative; @@ -431,7 +429,6 @@ FixedwingPositionControl::FixedwingPositionControl() : _parameter_handles.throttle_land_max = param_find("FW_THR_LND_MAX"); _parameter_handles.land_slope_angle = param_find("FW_LND_ANG"); - _parameter_handles.land_slope_length = param_find("FW_LND_SLLR"); _parameter_handles.land_H1_virt = param_find("FW_LND_HVIRT"); _parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT"); _parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT"); @@ -520,7 +517,6 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p)); param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle)); - param_get(_parameter_handles.land_slope_length, &(_parameters.land_slope_length)); param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt)); param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative)); param_get(_parameter_handles.land_thrust_lim_alt_relative, &(_parameters.land_thrust_lim_alt_relative)); @@ -889,7 +885,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float airspeed_land = 1.3f * _parameters.airspeed_min; float airspeed_approach = 1.3f * _parameters.airspeed_min; - float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)) * _parameters.land_slope_length; + float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)) * 0.9f; float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt); float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1)); float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt); 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 index 62a340e905..0909135e15 100644 --- 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 @@ -348,13 +348,6 @@ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); */ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); -/** - * Landing slope length - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f); - /** * * From b7488da441cf945ec1e5f0a1a4c4b6295707a8b0 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 19 Feb 2014 22:06:05 +0100 Subject: [PATCH 31/76] fw autoland: completely remove the virtual wp between the last wp and the landing wp. autoland starts now from the last normal wp. --- .../fw_pos_control_l1_main.cpp | 32 +++++++------------ 1 file changed, 11 insertions(+), 21 deletions(-) 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 index 020d1c119e..e1869328a1 100644 --- 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 @@ -885,7 +885,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float airspeed_land = 1.3f * _parameters.airspeed_min; float airspeed_approach = 1.3f * _parameters.airspeed_min; - float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)) * 0.9f; + float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)); float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt); float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1)); float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt); @@ -931,34 +931,24 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi //warnx("Landing: flare, _global_pos.alt %.1f, flare_curve_alt %.1f, flare_curve_alt_last %.1f, flare_length %.1f, wp_distance %.1f", _global_pos.alt, flare_curve_alt, flare_curve_alt_last, flare_length, wp_distance); flare_curve_alt_last = flare_curve_alt; - - } else if (wp_distance < L_wp_distance) { - - /* minimize speed to approach speed, stay on landing slope */ - _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, landing_slope_alt_desired, calculate_target_airspeed(airspeed_approach), - _airspeed.indicated_airspeed_m_s, eas2tas, - false, flare_pitch_angle_rad, - _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise, - math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max)); - //warnx("Landing: stay on slope, alt_desired: %.1f (wp_distance: %.1f), calculate_target_airspeed(airspeed_land) %.1f, horizontal_slope_displacement %.1f, d1 %.1f, flare_length %.1f", landing_slope_alt_desired, wp_distance, calculate_target_airspeed(airspeed_land), horizontal_slope_displacement, d1, flare_length); - - if (!land_onslope) { - - mavlink_log_info(_mavlink_fd, "#audio: Landing, on slope"); - land_onslope = true; - } - } else { /* intersect glide slope: - * if current position is higher or within 10m of slope follow the glide slope - * if current position is below slope -10m continue on maximum of previous wp altitude or L_altitude until the intersection with the slope - * */ + * minimize speed to approach speed + * if current position is higher or within 10m of slope follow the glide slope + * if current position is below slope -10m continue on maximum of previous wp altitude or L_altitude until the intersection with the slope + * */ float altitude_desired = _global_pos.alt; if (_global_pos.alt > landing_slope_alt_desired - 10.0f) { /* stay on slope */ altitude_desired = landing_slope_alt_desired; //warnx("Landing: before L, stay on landing slope, alt_desired: %.1f (wp_distance: %.1f, L_wp_distance %.1f), calculate_target_airspeed(airspeed_land) %.1f, horizontal_slope_displacement %.1f", altitude_desired, wp_distance, L_wp_distance, calculate_target_airspeed(airspeed_land), horizontal_slope_displacement); + + if (!land_onslope) { + mavlink_log_info(_mavlink_fd, "#audio: Landing, on slope"); + land_onslope = true; + } + } else { /* continue horizontally */ altitude_desired = math::max(_global_pos.alt, L_altitude); From 9830f668c548ed63131722cdbba4753e1c06f647 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 19 Feb 2014 22:55:40 +0100 Subject: [PATCH 32/76] fw autoland: fix warning --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 index e1869328a1..b0d2bcbc6d 100644 --- 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 @@ -912,7 +912,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float flare_curve_alt = landingslope.getFlareCurveAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt); /* avoid climbout */ - if (flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical || land_stayonground) + if ((flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical) || land_stayonground) { flare_curve_alt = pos_sp_triplet.current.alt; land_stayonground = true; From ae3e625ce8cec56527dc6809c0b48081773b47a3 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 19 Feb 2014 23:20:17 +0100 Subject: [PATCH 33/76] fw pos ctrl: initialize uorb structs in initialization list --- .../fw_pos_control_l1_main.cpp | 23 ++++++++----------- 1 file changed, 10 insertions(+), 13 deletions(-) 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 index 62c69d3ebe..1feb539b98 100644 --- 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 @@ -397,20 +397,17 @@ FixedwingPositionControl::FixedwingPositionControl() : _airspeed_error(0.0f), _airspeed_valid(false), _groundspeed_undershoot(0.0f), - _global_pos_valid(false) + _global_pos_valid(false), + _att(), + _att_sp(), + _nav_capabilities(), + _manual(), + _airspeed(), + _control_mode(), + _global_pos(), + _pos_sp_triplet(), + _sensor_combined() { - /* safely initialize structs */ - memset(&_att, 0, sizeof(vehicle_attitude_s)); - memset(&_att_sp, 0, sizeof(vehicle_attitude_setpoint_s)); - memset(&_nav_capabilities, 0, sizeof(navigation_capabilities_s)); - memset(&_manual, 0, sizeof(manual_control_setpoint_s)); - memset(&_airspeed, 0, sizeof(airspeed_s)); - memset(&_control_mode, 0, sizeof(vehicle_control_mode_s)); - memset(&_global_pos, 0, sizeof(vehicle_global_position_s)); - memset(&_pos_sp_triplet, 0, sizeof(position_setpoint_triplet_s)); - memset(&_sensor_combined, 0, sizeof(sensor_combined_s)); - - _nav_capabilities.turn_distance = 0.0f; _parameter_handles.l1_period = param_find("FW_L1_PERIOD"); From 60de15ea9d753eef3361778633f7f91fb92aa748 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 19 Feb 2014 23:26:50 +0100 Subject: [PATCH 34/76] fw autoland: remove old comments --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 4 ---- 1 file changed, 4 deletions(-) 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 index b0d2bcbc6d..3367aee9aa 100644 --- 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 @@ -942,17 +942,13 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi if (_global_pos.alt > landing_slope_alt_desired - 10.0f) { /* stay on slope */ altitude_desired = landing_slope_alt_desired; - //warnx("Landing: before L, stay on landing slope, alt_desired: %.1f (wp_distance: %.1f, L_wp_distance %.1f), calculate_target_airspeed(airspeed_land) %.1f, horizontal_slope_displacement %.1f", altitude_desired, wp_distance, L_wp_distance, calculate_target_airspeed(airspeed_land), horizontal_slope_displacement); - if (!land_onslope) { mavlink_log_info(_mavlink_fd, "#audio: Landing, on slope"); land_onslope = true; } - } else { /* continue horizontally */ altitude_desired = math::max(_global_pos.alt, L_altitude); - //warnx("Landing: before L,continue at: %.4f, (landing_slope_alt_desired %.4f, wp_distance: %.4f, L_altitude: %.4f L_wp_distance: %.4f)", altitude_desired, landing_slope_alt_desired, wp_distance, L_altitude, L_wp_distance); } _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, altitude_desired, calculate_target_airspeed(airspeed_approach), From b7899056f5454d8508a20dff87661c424ad98340 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 19 Feb 2014 23:32:55 +0100 Subject: [PATCH 35/76] fw autoland: add very short comment --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 ++ 1 file changed, 2 insertions(+) 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 index 3367aee9aa..64d2b70197 100644 --- 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 @@ -885,8 +885,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float airspeed_land = 1.3f * _parameters.airspeed_min; float airspeed_approach = 1.3f * _parameters.airspeed_min; + /* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */ float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)); float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt); + float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1)); float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt); From 2d97dff35c2976c7ba98e97a66b4a141cfb8960e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 21 Feb 2014 06:52:40 +0100 Subject: [PATCH 36/76] Added support for DX10t, which apparently outputs 13 channels --- src/modules/px4iofirmware/dsm.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index 60eda23192..70f31240a2 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -162,6 +162,7 @@ dsm_guess_format(bool reset) 0xff, /* 8 channels (DX8) */ 0x1ff, /* 9 channels (DX9, etc.) */ 0x3ff, /* 10 channels (DX10) */ + 0x1fff, /* 13 channels (DX10t) */ 0x3fff /* 18 channels (DX10) */ }; unsigned votes10 = 0; From 9828d5ede474723d83b189c394397d78c7050b7a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 21 Feb 2014 07:50:36 +0100 Subject: [PATCH 37/76] Fix copyright, do not return junk channel #13 that Spektrum gives us. --- src/modules/px4iofirmware/dsm.c | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index 70f31240a2..0d3eb26063 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-2014 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 @@ -401,6 +401,15 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) values[channel] = value; } + /* + * Spektrum likes to send junk in higher channel numbers to fill + * their packets. We don't know about a 13 channel model in their TX + * lines, so if we get a channel count of 13, we'll return 12 (the last + * data index that is stable). + */ + if (*num_values == 13) + *num_values = 12; + if (dsm_channel_shift == 11) { /* Set the 11-bit data indicator */ *num_values |= 0x8000; From b58fa2dffc22b3ba27ac87f1f514c298024cea4a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 18 Feb 2014 10:37:54 +0100 Subject: [PATCH 38/76] Change bit mask to allow for 10 channels. --- src/modules/px4iofirmware/registers.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 1335f52e13..97d25bbfa8 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -566,7 +566,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) break; case PX4IO_P_SETUP_DSM: - dsm_bind(value & 0x0f, (value >> 4) & 7); + dsm_bind(value & 0x0f, (value >> 4) & 0xF); break; default: From f1f1ecd096f2ad7b791127c9ee943a7dfc0ab3f4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 18 Feb 2014 10:36:46 +0100 Subject: [PATCH 39/76] Fix mavlink feedback FD handling --- src/drivers/px4io/px4io.cpp | 27 ++++++++++++--------------- 1 file changed, 12 insertions(+), 15 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index efcf4d12b9..13326e9625 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -244,8 +244,7 @@ private: volatile int _task; ///< worker task id volatile bool _task_should_exit; ///< worker terminate flag - int _mavlink_fd; ///< mavlink file descriptor. This is opened by class instantiation and Doesn't appear to be usable in main thread. - int _thread_mavlink_fd; ///< mavlink file descriptor for thread. + int _mavlink_fd; ///< mavlink file descriptor. perf_counter_t _perf_update; /// Date: Tue, 18 Feb 2014 10:37:11 +0100 Subject: [PATCH 40/76] Code style --- src/drivers/drv_pwm_output.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index c3eea310ff..7a93e513ed 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -160,7 +160,7 @@ ORB_DECLARE(output_pwm); #define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */ #define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */ -#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */ +#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */ /** power up DSM receiver */ #define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 11) From a91b68d8a52709c5ce3ce465cad3b7e5a5e34f66 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 18 Feb 2014 10:37:32 +0100 Subject: [PATCH 41/76] Fix DSM pairing error handling. --- src/drivers/px4io/px4io.cpp | 30 ++++++++++++++++++++---------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 13326e9625..7c7b3dcb7d 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2112,14 +2112,24 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) break; case DSM_BIND_START: - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); - usleep(500000); - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out); - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); - usleep(72000); - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); - usleep(50000); - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); + + /* only allow DSM2, DSM-X and DSM-X with more than 7 channels */ + if (arg == DSM2_BIND_PULSES || + arg == DSMX_BIND_PULSES || + arg == DSMX8_BIND_PULSES) { + io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); + usleep(500000); + io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out); + io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); + usleep(72000); + io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); + usleep(50000); + io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); + + ret = OK; + } else { + ret = -EINVAL; + } break; case DSM_BIND_POWER_UP: @@ -2612,7 +2622,7 @@ bind(int argc, char *argv[]) #endif if (argc < 3) - errx(0, "needs argument, use dsm2 or dsmx"); + errx(0, "needs argument, use dsm2, dsmx or dsmx8"); if (!strcmp(argv[2], "dsm2")) pulses = DSM2_BIND_PULSES; @@ -2621,7 +2631,7 @@ bind(int argc, char *argv[]) else if (!strcmp(argv[2], "dsmx8")) pulses = DSMX8_BIND_PULSES; else - errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]); + errx(1, "unknown parameter %s, use dsm2, dsmx or dsmx8", argv[2]); // Test for custom pulse parameter if (argc > 3) pulses = atoi(argv[3]); From 06b69b70a5d73ba32bc08cacedbeb9016a32195b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 21 Feb 2014 12:27:04 +0100 Subject: [PATCH 42/76] Scaling Spektrum inputs into normalized value same as the servo outputs do --- src/modules/px4iofirmware/dsm.c | 22 ++++++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index 0d3eb26063..aac2087b22 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -369,11 +369,25 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) if (channel >= *num_values) *num_values = channel + 1; - /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding in a very sloppy fashion */ - if (dsm_channel_shift == 11) - value /= 2; + /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */ + if (dsm_channel_shift == 10) + value *= 2; - value += 998; + /* + * Spektrum scaling is special. There are these basic considerations + * + * * Midpoint is 1520 us + * * 100% travel channels are +- 400 us + * + * We obey the original Spektrum scaling (so a default setup will scale from + * 1100 - 1900 us), but we do not obey the weird 1520 us center point + * and instead (correctly) center the center around 1500 us. This is in order + * to get something useful without requiring the user to calibrate on a digital + * link for no reason. + */ + + /* scaled integer for decent accuracy while staying efficient */ + value = (((value - 1024) * 1000) / 1700) + 1500; /* * Store the decoded channel into the R/C input buffer, taking into From 983cff56b3854aecf645773a1863ac01903b8c5a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 21 Feb 2014 12:50:29 +0100 Subject: [PATCH 43/76] Added int cast to handle arithmetic correctly --- src/modules/px4iofirmware/dsm.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index aac2087b22..d3f3658228 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -387,7 +387,7 @@ dsm_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values) */ /* scaled integer for decent accuracy while staying efficient */ - value = (((value - 1024) * 1000) / 1700) + 1500; + value = ((((int)value - 1024) * 1000) / 1700) + 1500; /* * Store the decoded channel into the R/C input buffer, taking into From f4bac7e7e802abf671d0ee87ad84b6f281fd81be Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Fri, 21 Feb 2014 20:22:05 +0100 Subject: [PATCH 44/76] navigator: remove all but one [navigator] tag from mavlink audio messages --- src/modules/navigator/navigator_main.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 2711be24fc..0268c47e73 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -865,7 +865,7 @@ Navigator::task_main() /* notify user about state changes */ if (myState != prevState) { - mavlink_log_info(_mavlink_fd, "#audio: [navigator] nav state: %s", nav_states_str[myState]); + mavlink_log_info(_mavlink_fd, "#audio: navigation state: %s", nav_states_str[myState]); prevState = myState; /* reset time counter on state changes */ @@ -1073,11 +1073,11 @@ Navigator::start_loiter() /* use current altitude if above min altitude set by parameter */ if (_global_pos.alt < min_alt_amsl) { _pos_sp_triplet.current.alt = min_alt_amsl; - mavlink_log_info(_mavlink_fd, "#audio: [navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt)); + mavlink_log_info(_mavlink_fd, "#audio: loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt)); } else { _pos_sp_triplet.current.alt = _global_pos.alt; - mavlink_log_info(_mavlink_fd, "#audio: [navigator] loiter at current altitude"); + mavlink_log_info(_mavlink_fd, "#audio: loiter at current altitude"); } _pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER; @@ -1175,14 +1175,14 @@ Navigator::set_mission_item() } if (_do_takeoff) { - mavlink_log_info(_mavlink_fd, "#audio: [navigator] takeoff to %.1fm above home", _pos_sp_triplet.current.alt - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: takeoff to %.1fm above home", _pos_sp_triplet.current.alt - _home_pos.alt); } else { if (onboard) { - mavlink_log_info(_mavlink_fd, "#audio: [navigator] heading to onboard WP %d", index); + mavlink_log_info(_mavlink_fd, "#audio: heading to onboard WP %d", index); } else { - mavlink_log_info(_mavlink_fd, "#audio: [navigator] heading to offboard WP %d", index); + mavlink_log_info(_mavlink_fd, "#audio: heading to offboard WP %d", index); } } @@ -1331,7 +1331,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "#audio: [navigator] RTL: climb to %.1fm above home", climb_alt - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: RTL: climb to %.1fm above home", climb_alt - _home_pos.alt); break; } @@ -1357,7 +1357,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "#audio: [navigator] RTL: return at %.1fm above home", _mission_item.altitude - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: RTL: return at %.1fm above home", _mission_item.altitude - _home_pos.alt); break; } @@ -1384,7 +1384,7 @@ Navigator::set_rtl_item() _pos_sp_triplet.next.valid = false; - mavlink_log_info(_mavlink_fd, "#audio: [navigator] RTL: descend to %.1fm above home", _mission_item.altitude - _home_pos.alt); + mavlink_log_info(_mavlink_fd, "#audio: RTL: descend to %.1fm above home", _mission_item.altitude - _home_pos.alt); break; } @@ -1516,7 +1516,7 @@ Navigator::check_mission_item_reached() _time_first_inside_orbit = now; if (_mission_item.time_inside > 0.01f) { - mavlink_log_info(_mavlink_fd, "#audio: [navigator] waypoint reached, wait for %.1fs", _mission_item.time_inside); + mavlink_log_info(_mavlink_fd, "#audio: waypoint reached, wait for %.1fs", _mission_item.time_inside); } } @@ -1541,7 +1541,7 @@ Navigator::on_mission_item_reached() if (_do_takeoff) { /* takeoff completed */ _do_takeoff = false; - mavlink_log_info(_mavlink_fd, "#audio: [navigator] takeoff completed"); + mavlink_log_info(_mavlink_fd, "#audio: takeoff completed"); } else { /* advance by one mission item */ From ff8f92af31fe1eadb52dbe1e612fd1f31b00ff82 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 23 Feb 2014 07:24:03 -0800 Subject: [PATCH 45/76] Remove Ubuntu code style script - people should use the reference one --- Tools/fix_code_style_ubuntu.sh | 19 ------------------- 1 file changed, 19 deletions(-) delete mode 100755 Tools/fix_code_style_ubuntu.sh diff --git a/Tools/fix_code_style_ubuntu.sh b/Tools/fix_code_style_ubuntu.sh deleted file mode 100755 index 90ab57b895..0000000000 --- a/Tools/fix_code_style_ubuntu.sh +++ /dev/null @@ -1,19 +0,0 @@ -#!/bin/sh -astyle \ - --style=linux \ - --indent=force-tab=8 \ - --indent-cases \ - --indent-preprocessor \ - --break-blocks=all \ - --pad-oper \ - --pad-header \ - --unpad-paren \ - --keep-one-line-blocks \ - --keep-one-line-statements \ - --align-pointer=name \ - --suffix=none \ - --lineend=linux \ - $* - #--ignore-exclude-errors-x \ - #--exclude=EASTL \ - #--align-reference=name \ From 99b376089f6a35c977174ae8e01bc4686b405cc7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 23 Feb 2014 07:26:23 -0800 Subject: [PATCH 46/76] Replace single if lines with brackets in astyle --- Tools/fix_code_style.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/fix_code_style.sh b/Tools/fix_code_style.sh index 832ee79da6..0b6743013f 100755 --- a/Tools/fix_code_style.sh +++ b/Tools/fix_code_style.sh @@ -16,4 +16,5 @@ astyle \ --ignore-exclude-errors-x \ --lineend=linux \ --exclude=EASTL \ + --add-brackets \ $* From 20618a611b5cd719cab803823b2f3a08d9a498f6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 23 Feb 2014 12:44:05 -0800 Subject: [PATCH 47/76] Fixed a number of compile warnings in mount tests. --- src/systemcmds/tests/test_mount.c | 38 ++++++++++++++----------------- 1 file changed, 17 insertions(+), 21 deletions(-) diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c index 44e34d9ef3..4b6303cfb1 100644 --- a/src/systemcmds/tests/test_mount.c +++ b/src/systemcmds/tests/test_mount.c @@ -141,8 +141,8 @@ test_mount(int argc, char *argv[]) /* announce mode switch */ if (it_left_fsync_prev != it_left_fsync && it_left_fsync == 0) { warnx("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC"); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(20000); } @@ -162,7 +162,7 @@ test_mount(int argc, char *argv[]) } char buf[64]; - int wret = sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort); + (void)sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort); lseek(cmd_fd, 0, SEEK_SET); write(cmd_fd, buf, strlen(buf) + 1); fsync(cmd_fd); @@ -174,8 +174,8 @@ test_mount(int argc, char *argv[]) printf("\n\n====== FILE TEST: %u bytes chunks (%s) ======\n", chunk_sizes[c], (it_left_fsync > 0) ? "FSYNC" : "NO FSYNC"); printf("unpower the system immediately (within 0.5s) when the hash (#) sign appears\n"); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(50000); for (unsigned a = 0; a < alignments; a++) { @@ -185,22 +185,20 @@ test_mount(int argc, char *argv[]) uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); /* fill write buffer with known values */ - for (int i = 0; i < sizeof(write_buf); i++) { + for (unsigned i = 0; i < sizeof(write_buf); i++) { /* this will wrap, but we just need a known value with spacing */ write_buf[i] = i+11; } uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); - hrt_abstime start, end; int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); - start = hrt_absolute_time(); for (unsigned i = 0; i < iterations; i++) { int wret = write(fd, write_buf + a, chunk_sizes[c]); - if (wret != chunk_sizes[c]) { + if (wret != (int)chunk_sizes[c]) { warn("WRITE ERROR!"); if ((0x3 & (uintptr_t)(write_buf + a))) @@ -214,8 +212,8 @@ test_mount(int argc, char *argv[]) fsync(fd); } else { printf("#"); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); } } @@ -224,12 +222,10 @@ test_mount(int argc, char *argv[]) } printf("."); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(200000); - end = hrt_absolute_time(); - close(fd); fd = open("/fs/microsd/testfile", O_RDONLY); @@ -237,7 +233,7 @@ test_mount(int argc, char *argv[]) for (unsigned i = 0; i < iterations; i++) { int rret = read(fd, read_buf, chunk_sizes[c]); - if (rret != chunk_sizes[c]) { + if (rret != (int)chunk_sizes[c]) { warnx("READ ERROR!"); return 1; } @@ -245,7 +241,7 @@ test_mount(int argc, char *argv[]) /* compare value */ bool compare_ok = true; - for (int j = 0; j < chunk_sizes[c]; j++) { + for (unsigned j = 0; j < chunk_sizes[c]; j++) { if (read_buf[j] != write_buf[j + a]) { warnx("COMPARISON ERROR: byte %d, align shift: %d", j, a); compare_ok = false; @@ -271,16 +267,16 @@ test_mount(int argc, char *argv[]) } } - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(20000); /* we always reboot for the next test if we get here */ warnx("Iteration done, rebooting.."); - fsync(stdout); - fsync(stderr); + fsync(fileno(stdout)); + fsync(fileno(stderr)); usleep(50000); systemreset(false); From e1f60e770948d28ec1152f66b9c3ad57eae0c2e4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 23 Feb 2014 12:53:20 -0800 Subject: [PATCH 48/76] Code style fixes (authors should be in the doxygen section), using lseek to attempt to work around log corruption --- src/modules/sdlog2/logbuffer.c | 3 +-- src/modules/sdlog2/sdlog2.c | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c index b3243f7b5a..6a29d7e5c9 100644 --- a/src/modules/sdlog2/logbuffer.c +++ b/src/modules/sdlog2/logbuffer.c @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013 PX4 Development Team. All rights reserved. - * Author: Anton Babushkin + * Copyright (c) 2013, 2014 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 diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index c4fafb5a66..16c37459b5 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1,8 +1,6 @@ /**************************************************************************** * * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier - * Anton Babushkin * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -95,6 +93,7 @@ #define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \ log_msgs_written++; \ + } else { \ log_msgs_skipped++; \ } @@ -450,6 +449,7 @@ static void *logwriter_thread(void *arg) n = available; } + lseek(log_fd, 0, SEEK_CUR); n = write(log_fd, read_ptr, n); should_wait = (n == available) && !is_part; From ab8ece3961f50348cf4bf464cb7d953b182a0a44 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 24 Feb 2014 12:42:48 +0100 Subject: [PATCH 49/76] l1_pos_control: prevent NaNs for roll setpoint --- src/lib/ecl/l1/ecl_l1_pos_controller.cpp | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp index 3b68a0a4e8..d1c864d782 100644 --- a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp +++ b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp @@ -38,6 +38,8 @@ * */ +#include + #include "ecl_l1_pos_controller.h" float ECL_L1_Pos_Controller::nav_roll() @@ -231,8 +233,15 @@ void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector<2> &vector_A, con /* calculate the vector from waypoint A to current position */ math::Vector<2> vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position); - /* store the normalized vector from waypoint A to current position */ - math::Vector<2> vector_A_to_airplane_unit = (vector_A_to_airplane).normalized(); + math::Vector<2> vector_A_to_airplane_unit; + + /* prevent NaN when normalizing */ + if (vector_A_to_airplane.length() > FLT_EPSILON) { + /* store the normalized vector from waypoint A to current position */ + vector_A_to_airplane_unit = vector_A_to_airplane.normalized(); + } else { + vector_A_to_airplane_unit = vector_A_to_airplane; + } /* calculate eta angle towards the loiter center */ From 75c6706278119e50ce56ecbb1620025a9b9b936d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 24 Feb 2014 14:19:57 +0100 Subject: [PATCH 50/76] l1_pos_control: set gndspeed_undershoot to 0 in loiter --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 index ed57e0d349..2e8d038d0d 100644 --- 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 @@ -695,7 +695,7 @@ void FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector<2> ¤t_position, const math::Vector<2> &ground_speed, const struct position_setpoint_triplet_s &pos_sp_triplet) { - if (_global_pos_valid) { + if (_global_pos_valid && !pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER) { /* rotate ground speed vector with current attitude */ math::Vector<2> yaw_vector(_R_nb(0, 0), _R_nb(1, 0)); From 909e138182000350df19d47367d6f68d0a6b7fd4 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 24 Feb 2014 14:27:24 +0100 Subject: [PATCH 51/76] l1_pos_control: fix stupid 'if not' mistake --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 index 2e8d038d0d..ed6d8792ce 100644 --- 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 @@ -695,7 +695,7 @@ void FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector<2> ¤t_position, const math::Vector<2> &ground_speed, const struct position_setpoint_triplet_s &pos_sp_triplet) { - if (_global_pos_valid && !pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER) { + if (_global_pos_valid && !(pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER)) { /* rotate ground speed vector with current attitude */ math::Vector<2> yaw_vector(_R_nb(0, 0), _R_nb(1, 0)); From ba0bf456b9b0cf6cdc58ce2fd80192da3c1744d2 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 24 Feb 2014 15:37:35 +0100 Subject: [PATCH 52/76] gitignore: ignore pydev project file created in eclipse --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 3e94cf6205..71326517f2 100644 --- a/.gitignore +++ b/.gitignore @@ -35,3 +35,4 @@ mavlink/include/mavlink/v0.9/ /Documentation/doxygen*objdb*tmp .tags .tags_sorted_by_file +.pydevproject From 5ed5e04cb24c261c9a8b40857bd1d733238f847e Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 24 Feb 2014 15:43:23 +0100 Subject: [PATCH 53/76] sdlog2: code style fixes broke compilation --- src/modules/sdlog2/sdlog2.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 16c37459b5..41e2248bbe 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -93,7 +93,6 @@ #define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \ log_msgs_written++; \ - } else { \ log_msgs_skipped++; \ } From a79eef05bcb23c9be386a2980437a67151cfa3ea Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 24 Feb 2014 23:48:00 +0400 Subject: [PATCH 54/76] perf_counter: added include --- src/modules/systemlib/perf_counter.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h index e1e3cbe95e..d8f69fdbf7 100644 --- a/src/modules/systemlib/perf_counter.h +++ b/src/modules/systemlib/perf_counter.h @@ -39,6 +39,8 @@ #ifndef _SYSTEMLIB_PERF_COUNTER_H #define _SYSTEMLIB_PERF_COUNTER_H value +#include + /** * Counter types. */ From f8187650083b361f61c07ceb712c21a25d1c80c4 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 27 Feb 2014 18:32:55 +0400 Subject: [PATCH 55/76] top: CPU % indication bug fixed --- src/systemcmds/top/top.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c index 1ca3fc9281..37e913040d 100644 --- a/src/systemcmds/top/top.c +++ b/src/systemcmds/top/top.c @@ -233,8 +233,8 @@ top_main(void) system_load.tasks[i].tcb->pid, CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name, (system_load.tasks[i].total_runtime / 1000), - (int)(curr_loads[i] * 100), - (int)(curr_loads[i] * 100000.0f - (int)(curr_loads[i] * 1000.0f) * 100), + (int)(curr_loads[i] * 100.0f), + (int)((curr_loads[i] * 100.0f - (int)(curr_loads[i] * 100.0f)) * 1000), stack_size - stack_free, stack_size, system_load.tasks[i].tcb->sched_priority, From eac00a71ea8f0b10d446be752f6fef737f850956 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 1 Mar 2014 11:05:07 +0100 Subject: [PATCH 56/76] navigator: don't enter AUTO_READY for fixedwing because we don't have a land detector yet --- src/modules/navigator/navigator_main.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 04f87d4caf..8d0710e915 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1386,7 +1386,8 @@ Navigator::set_rtl_item() void Navigator::request_loiter_or_ready() { - if (_vstatus.condition_landed) { + /* XXX workaround: no landing detector for fixedwing yet */ + if (_vstatus.condition_landed && _vstatus.is_rotary_wing) { dispatch(EVENT_READY_REQUESTED); } else { From b264352c179dafd42066ca8ffbdf855c7f111207 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 1 Mar 2014 15:47:09 +0100 Subject: [PATCH 57/76] startup: phantom script was missing the default line --- ROMFS/px4fmu_common/init.d/3031_phantom | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index 2e2434bb85..a3004d1e13 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -5,4 +5,6 @@ # Simon Wilks # +sh /etc/init.d/rc.fw_defaults + set MIXER FMU_Q From e06263f76f9e38ea9624f1f1ab21af8731a3cd7f Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Mar 2014 22:43:56 +0400 Subject: [PATCH 58/76] position_estimator_inav: failsafe against NaN estimate --- .../position_estimator_inav_main.c | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) 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 ad363efe06..fb68dd31c0 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -708,6 +708,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p); inertial_filter_correct(corr_acc[2], dt, z_est, 2, params.w_z_acc); + float x_est_prev[3], y_est_prev[3]; + + memcpy(x_est_prev, x_est, sizeof(x_est)); + memcpy(y_est_prev, y_est, sizeof(y_est)); + if (can_estimate_xy) { /* inertial filter prediction for position */ inertial_filter_predict(dt, x_est); @@ -715,7 +720,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) if (!isfinite(x_est[0]) || !isfinite(y_est[0])) { write_debug_log("BAD ESTIMATE AFTER PREDICTION", dt, x_est, y_est, z_est, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v); - thread_should_exit = true; + memcpy(x_est, x_est_prev, sizeof(x_est)); + memcpy(y_est, y_est_prev, sizeof(y_est)); } /* inertial filter correction for position */ @@ -739,7 +745,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) if (!isfinite(x_est[0]) || !isfinite(y_est[0])) { write_debug_log("BAD ESTIMATE AFTER CORRECTION", dt, x_est, y_est, z_est, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v); - thread_should_exit = true; + memcpy(x_est, x_est_prev, sizeof(x_est)); + memcpy(y_est, y_est_prev, sizeof(y_est)); + memset(corr_acc, 0, sizeof(corr_acc)); + memset(corr_gps, 0, sizeof(corr_gps)); + memset(corr_flow, 0, sizeof(corr_flow)); } } From d11235585cf1014c5391b63e394151c171ed286d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 1 Mar 2014 22:56:02 +0400 Subject: [PATCH 59/76] position_estimator_inav: log writing on NaN estimate fixed --- .../position_estimator_inav_main.c | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) 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 fb68dd31c0..d6d03367b6 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -167,12 +167,13 @@ void write_debug_log(const char *msg, float dt, float x_est[3], float y_est[3], FILE *f = fopen("/fs/microsd/inav.log", "a"); if (f) { char *s = malloc(256); - snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f %.5f] y_est=[%.5f %.5f %.5f] z_est=[%.5f %.5f %.5f]\n", hrt_absolute_time(), msg, dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2], z_est[0], z_est[1], z_est[2]); - fputs(f, s); - snprintf(s, 256, "\tacc_corr=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n", corr_acc[0], corr_acc[1], corr_acc[2], corr_gps[0][0], corr_gps[1][0], corr_gps[2][0], corr_gps[0][1], corr_gps[1][1], corr_gps[2][1], w_xy_gps_p, w_xy_gps_v); - fputs(f, s); + unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f %.5f] y_est=[%.5f %.5f %.5f] z_est=[%.5f %.5f %.5f]\n", hrt_absolute_time(), msg, dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2], z_est[0], z_est[1], z_est[2]); + fwrite(s, 1, n, f); + n = snprintf(s, 256, "\tacc_corr=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n", corr_acc[0], corr_acc[1], corr_acc[2], corr_gps[0][0], corr_gps[1][0], corr_gps[2][0], corr_gps[0][1], corr_gps[1][1], corr_gps[2][1], w_xy_gps_p, w_xy_gps_v); + fwrite(s, 1, n, f); free(s); } + fsync(fileno(f)); fclose(f); } From db157b68c2f3dba4209f8075f6ae7ae9e81a448c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 2 Mar 2014 19:42:10 +0400 Subject: [PATCH 60/76] mc_pos_control: remove some debug logs --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index b4bac53d66..78d06ba5b5 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -791,7 +791,6 @@ MulticopterPositionControl::task_main() } thrust_int(2) = -i; - mavlink_log_info(_mavlink_fd, "[mpc] reset hovering thrust: %.2f", (double)i); } } else { @@ -803,7 +802,6 @@ MulticopterPositionControl::task_main() reset_int_xy = false; thrust_int(0) = 0.0f; thrust_int(1) = 0.0f; - mavlink_log_info(_mavlink_fd, "[mpc] reset xy vel integral"); } } else { From 3674aae4a746099a162cbf943311b587cd46822f Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 3 Mar 2014 21:19:56 +0400 Subject: [PATCH 61/76] commander: ignore battery voltage in HIL mode --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index d5af63120b..483437029b 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -962,7 +962,7 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(battery_status), battery_sub, &battery); /* only consider battery voltage if system has been running 2s and battery voltage is valid */ - if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) { + if (status.hil_state == HIL_STATE_OFF && hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) { status.battery_voltage = battery.voltage_filtered_v; status.battery_current = battery.current_a; status.condition_battery_voltage_valid = true; From b76e26c5e5f37c4fb086a68e0427d9d297e8d225 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 3 Mar 2014 21:24:59 +0400 Subject: [PATCH 62/76] commander: allow arming with safety enabled in HIL mode --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 483437029b..d114a2e5ce 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -902,7 +902,7 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(safety), safety_sub, &safety); /* disarm if safety is now on and still armed */ - if (safety.safety_switch_available && !safety.safety_off && armed.armed) { + if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) { arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed)) { mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch"); From a7012a54180386b5dc7f86fe6a1564690ecc8240 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 4 Mar 2014 08:34:55 +1100 Subject: [PATCH 63/76] tests: added "tests file2" filesystem test this is useful for testing for filesystem corruption on cluster boundaries --- src/systemcmds/tests/module.mk | 1 + src/systemcmds/tests/test_file2.c | 196 ++++++++++++++++++++++++++++++ src/systemcmds/tests/tests.h | 1 + src/systemcmds/tests/tests_main.c | 1 + 4 files changed, 199 insertions(+) create mode 100644 src/systemcmds/tests/test_file2.c diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk index acf28c35b2..622a0faf3d 100644 --- a/src/systemcmds/tests/module.mk +++ b/src/systemcmds/tests/module.mk @@ -26,6 +26,7 @@ SRCS = test_adc.c \ test_mixer.cpp \ test_mathlib.cpp \ test_file.c \ + test_file2.c \ tests_main.c \ test_param.c \ test_ppm_loopback.c \ diff --git a/src/systemcmds/tests/test_file2.c b/src/systemcmds/tests/test_file2.c new file mode 100644 index 0000000000..ef555f6c34 --- /dev/null +++ b/src/systemcmds/tests/test_file2.c @@ -0,0 +1,196 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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. + * + ****************************************************************************/ + +/** + * @file test_file2.c + * + * File write test. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define FLAG_FSYNC 1 +#define FLAG_LSEEK 2 + +/* + return a predictable value for any file offset to allow detection of corruption + */ +static uint8_t get_value(uint32_t ofs) +{ + union { + uint32_t ofs; + uint8_t buf[4]; + } u; + u.ofs = ofs; + return u.buf[ofs % 4]; +} + +static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t write_size, uint16_t flags) +{ + printf("Testing on %s with write_chunk=%u write_size=%u\n", + filename, (unsigned)write_chunk, (unsigned)write_size); + + uint32_t ofs = 0; + int fd = open(filename, O_CREAT | O_RDWR | O_TRUNC); + if (fd == -1) { + perror(filename); + exit(1); + } + + // create a file of size write_size, in write_chunk blocks + uint8_t counter = 0; + while (ofs < write_size) { + uint8_t buffer[write_chunk]; + for (uint16_t j=0; j 0) { + filename = argv[0]; + } + + /* check if microSD card is mounted */ + struct stat buffer; + if (stat("/fs/microsd/", &buffer)) { + warnx("no microSD card mounted, aborting file test"); + return 1; + } + + test_corruption(filename, write_chunk, write_size, flags); + return 0; +} + diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h index ac64ad33d3..ad55e14102 100644 --- a/src/systemcmds/tests/tests.h +++ b/src/systemcmds/tests/tests.h @@ -107,6 +107,7 @@ extern int test_jig_voltages(int argc, char *argv[]); extern int test_param(int argc, char *argv[]); extern int test_bson(int argc, char *argv[]); extern int test_file(int argc, char *argv[]); +extern int test_file2(int argc, char *argv[]); extern int test_mixer(int argc, char *argv[]); extern int test_rc(int argc, char *argv[]); extern int test_conv(int argc, char *argv[]); diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c index 73827b7cf0..fe22f61773 100644 --- a/src/systemcmds/tests/tests_main.c +++ b/src/systemcmds/tests/tests_main.c @@ -104,6 +104,7 @@ const struct { {"param", test_param, 0}, {"bson", test_bson, 0}, {"file", test_file, 0}, + {"file2", test_file2, OPT_NOJIGTEST | OPT_NOALLTEST}, {"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST}, {"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST}, {"conv", test_conv, OPT_NOJIGTEST | OPT_NOALLTEST}, From ea70e967565a15ffc06aeb95df87f47440df97c1 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Tue, 4 Mar 2014 16:16:39 +0100 Subject: [PATCH 64/76] Added ARDrone to autostart --- ROMFS/px4fmu_common/init.d/rc.autostart | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 3968af58ea..7aaf7133ef 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -106,6 +106,15 @@ then sh /etc/init.d/4001_quad_x fi +# +# ARDrone +# + +if param compare SYS_AUTOSTART 4008 8 +then + sh /etc/init.d/4008_ardrone +fi + if param compare SYS_AUTOSTART 4010 10 then sh /etc/init.d/4010_dji_f330 From 958f7597e7d13f82e41b9c8e0aa4c3ac552cdf1c Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Tue, 4 Mar 2014 16:33:18 +0100 Subject: [PATCH 65/76] Added actual ARDrone start up script. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 40 +++++++++++++++++++++++++ 1 file changed, 40 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/4008_ardrone diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone new file mode 100644 index 0000000000..fa9b9d18a1 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -0,0 +1,40 @@ +#!nsh +# +# ARDrone +# + +# Just use the default multicopter settings. +sh /etc/init.d/rc.mc_defaults + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set MC_ATTRATE_D 0 + param set MC_ATTRATE_I 0 + param set MC_ATTRATE_P 0.13 + param set MC_ATT_D 0 + param set MC_ATT_I 0.3 + param set MC_ATT_P 5 + param set MC_YAWPOS_D 0.1 + param set MC_YAWPOS_I 0.15 + param set MC_YAWPOS_P 1 + param set MC_YAWRATE_D 0 + param set MC_YAWRATE_I 0 + param set MC_YAWRATE_P 0.15 + + param set SYS_AUTOCONFIG 0 + param save +fi + +set FMU_MODE gpio + +# +# Force some key parameters to sane values +# MAV_TYPE 2 = quadrotor +# +set MAV_TYPE 2 +set VEHICLE_TYPE mc +param set BAT_V_SCALING 0.008381 From 9817922bf96611f59552b6a6fd2aebab790135f5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 4 Mar 2014 20:34:20 +1100 Subject: [PATCH 66/76] FMUv2: switch debug console and 2nd GPS this allows a normal GPS cable to be used for the 2nd GPS, making dual-GPS setups easier --- nuttx-configs/px4fmu-v2/nsh/defconfig | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig index 2a734c27e5..26222c255d 100644 --- a/nuttx-configs/px4fmu-v2/nsh/defconfig +++ b/nuttx-configs/px4fmu-v2/nsh/defconfig @@ -306,7 +306,7 @@ CONFIG_UART5_RXDMA=y # CONFIG_USART6_RS485 is not set CONFIG_USART6_RXDMA=y # CONFIG_UART7_RS485 is not set -# CONFIG_UART7_RXDMA is not set +CONFIG_UART7_RXDMA=y # CONFIG_UART8_RS485 is not set CONFIG_UART8_RXDMA=y CONFIG_SERIAL_DISABLE_REORDERING=y @@ -539,8 +539,8 @@ CONFIG_SERIAL_NPOLLWAITERS=2 # CONFIG_USART3_SERIAL_CONSOLE is not set # CONFIG_UART4_SERIAL_CONSOLE is not set # CONFIG_USART6_SERIAL_CONSOLE is not set -# CONFIG_UART7_SERIAL_CONSOLE is not set -CONFIG_UART8_SERIAL_CONSOLE=y +CONFIG_UART7_SERIAL_CONSOLE=y +# CONFIG_UART8_SERIAL_CONSOLE is not set # CONFIG_NO_SERIAL_CONSOLE is not set # From 3639c7ae91f5226b71cdba8d8cc98eae4bba7e07 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 4 Mar 2014 21:36:09 +0100 Subject: [PATCH 67/76] Fixed warning --- src/modules/px4iofirmware/mixer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 6a44294619..dfa98d425c 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -327,7 +327,7 @@ mixer_handle_text(const void *buffer, size_t length) return 1; } - px4io_mixdata *msg = (px4io_mixdata *)buffer; + px4io_mixdata *msg = static_cast(buffer); isr_debug(2, "mix txt %u", length); From fabef6c889f0fc347e0059ee6f8ede83bf0f4f32 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 4 Mar 2014 22:52:34 +0100 Subject: [PATCH 68/76] Revert "Fixed warning" This reverts commit 3639c7ae91f5226b71cdba8d8cc98eae4bba7e07. --- src/modules/px4iofirmware/mixer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index dfa98d425c..6a44294619 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -327,7 +327,7 @@ mixer_handle_text(const void *buffer, size_t length) return 1; } - px4io_mixdata *msg = static_cast(buffer); + px4io_mixdata *msg = (px4io_mixdata *)buffer; isr_debug(2, "mix txt %u", length); From 1d9d24f605aeb13b87efe2f6cf82232768b148ac Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 10:50:16 +0100 Subject: [PATCH 69/76] Added flag for ARDrone interface. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 14 +++++--------- ROMFS/px4fmu_common/init.d/rcS | 12 +++++++++++- src/drivers/px4fmu/fmu.cpp | 2 +- 3 files changed, 17 insertions(+), 11 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index fa9b9d18a1..d6b2319f94 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -3,6 +3,8 @@ # ARDrone # +echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board" + # Just use the default multicopter settings. sh /etc/init.d/rc.mc_defaults @@ -29,12 +31,6 @@ then param save fi -set FMU_MODE gpio - -# -# Force some key parameters to sane values -# MAV_TYPE 2 = quadrotor -# -set MAV_TYPE 2 -set VEHICLE_TYPE mc -param set BAT_V_SCALING 0.008381 +set FMU_MODE gpio_serial +set OUTPUT_MODE fmu +set ARDRONE yes \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 76f021e339..af78162ed5 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -397,8 +397,10 @@ then set EXIT_ON_END yes else # Start MAVLink on default port: ttyS1 - mavlink start + mavlink start -d /dev/ttyS0 usleep 5000 + + set EXIT_ON_END yes fi fi @@ -427,6 +429,14 @@ then gps start fi + # + # Start up ARDrone Motor interface + # + if [ $ARDRONE == yes ] + then + ardrone_interface start -d /dev/ttyS1 + fi + # # Fixed wing setup # diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 0fbd849243..a70ff6c5c5 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -1714,7 +1714,7 @@ fmu_main(int argc, char *argv[]) } - fprintf(stderr, "FMU: unrecognised command, try:\n"); + fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb); #if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n"); #elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) From 9ffa5a665a2ac8b887cbd9383eab1947137f0def Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 10:56:58 +0100 Subject: [PATCH 70/76] Set the mavlink port settings back to ttyS1 by default. --- ROMFS/px4fmu_common/init.d/rcS | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index af78162ed5..1baac0eb3a 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -387,7 +387,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes ] + if [ $TTYS1_BUSY == yes -o $ARDRONE == yes] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0 @@ -397,10 +397,8 @@ then set EXIT_ON_END yes else # Start MAVLink on default port: ttyS1 - mavlink start -d /dev/ttyS0 + mavlink start usleep 5000 - - set EXIT_ON_END yes fi fi From 5976815f2baff6b17ca41dbb28e3e5698c12a180 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 15:07:05 +0100 Subject: [PATCH 71/76] Fixed startup parameters. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 29 ++++++++++++------------- ROMFS/px4fmu_common/init.d/rcS | 2 +- 2 files changed, 15 insertions(+), 16 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index d6b2319f94..d38796cca0 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -11,24 +11,23 @@ sh /etc/init.d/rc.mc_defaults # # Load default params for this platform # -if param compare SYS_AUTOCONFIG 1 +if [ $DO_AUTOCONFIG == yes ] then # Set all params here, then disable autoconfig - param set MC_ATTRATE_D 0 - param set MC_ATTRATE_I 0 - param set MC_ATTRATE_P 0.13 - param set MC_ATT_D 0 - param set MC_ATT_I 0.3 - param set MC_ATT_P 5 - param set MC_YAWPOS_D 0.1 - param set MC_YAWPOS_I 0.15 - param set MC_YAWPOS_P 1 - param set MC_YAWRATE_D 0 - param set MC_YAWRATE_I 0 + param set MC_ROLL_P 5.0 + param set MC_ROLLRATE_P 0.13 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.0 + param set MC_PITCH_P 5.0 + param set MC_PITCHRATE_P 0.13 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.0 + param set MC_YAW_P 1.0 + param set MC_YAW_D 0.1 param set MC_YAWRATE_P 0.15 - - param set SYS_AUTOCONFIG 0 - param save + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 + param set MC_YAW_FF 0.15 fi set FMU_MODE gpio_serial diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 1baac0eb3a..9983aa0e77 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -387,7 +387,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes -o $ARDRONE == yes] + if [ $TTYS1_BUSY == yes -o $ARDRONE == yes ] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0 From 30665816f0005cfb32b048a9ad4db84f78b3eff3 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 15:11:41 +0100 Subject: [PATCH 72/76] Added a newline at the end of file. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index d38796cca0..cb8260cccb 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -32,4 +32,4 @@ fi set FMU_MODE gpio_serial set OUTPUT_MODE fmu -set ARDRONE yes \ No newline at end of file +set ARDRONE yes From bcdc8c9e1dcefc2176fd1f853d4bae90e7d196d6 Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Wed, 5 Mar 2014 16:16:10 +0100 Subject: [PATCH 73/76] Get rid of one set of beeps. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index cb8260cccb..512c4cb736 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -33,3 +33,4 @@ fi set FMU_MODE gpio_serial set OUTPUT_MODE fmu set ARDRONE yes +set USE_IO no From 36ba60d63c024c23efdb4bba780ac98b5b257ee6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 5 Mar 2014 20:03:21 +0400 Subject: [PATCH 74/76] mc_att_control: hotfix, memset all structs to zeroes on start, fixes garbage in actuator controls 4..8 --- src/modules/mc_att_control/mc_att_control_main.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 24226880ed..9cb8e83445 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -262,8 +262,10 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() : { memset(&_v_att, 0, sizeof(_v_att)); memset(&_v_att_sp, 0, sizeof(_v_att_sp)); + memset(&_v_rates_sp, 0, sizeof(_v_rates_sp)); memset(&_manual_control_sp, 0, sizeof(_manual_control_sp)); memset(&_v_control_mode, 0, sizeof(_v_control_mode)); + memset(&_actuators, 0, sizeof(_actuators)); memset(&_armed, 0, sizeof(_armed)); _params.att_p.zero(); From a897c97d955de4873aea1f01f65cab11faab2d3a Mon Sep 17 00:00:00 2001 From: Helen Oleynikova Date: Thu, 6 Mar 2014 12:45:10 +0100 Subject: [PATCH 75/76] Changed ARDRONE to an OUTPUT_MODE setting and added a skip option to mixer. Fewer beeps than before. --- ROMFS/px4fmu_common/init.d/4008_ardrone | 5 ++--- ROMFS/px4fmu_common/init.d/rc.interface | 9 ++++++--- ROMFS/px4fmu_common/init.d/rcS | 13 +++++++++---- 3 files changed, 17 insertions(+), 10 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index 512c4cb736..39fe66234b 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -30,7 +30,6 @@ then param set MC_YAW_FF 0.15 fi -set FMU_MODE gpio_serial -set OUTPUT_MODE fmu -set ARDRONE yes +set OUTPUT_MODE ardrone set USE_IO no +set MIXER skip \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index d25f01dde0..afe71460de 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -3,7 +3,7 @@ # Script to configure control interface # -if [ $MIXER != none ] +if [ $MIXER != none -a $MIXER != skip] then # # Load mixer @@ -33,8 +33,11 @@ then tone_alarm $TUNE_OUT_ERROR fi else - echo "[init] Mixer not defined" - tone_alarm $TUNE_OUT_ERROR + if [ $MIXER != skip ] + then + echo "[init] Mixer not defined" + tone_alarm $TUNE_OUT_ERROR + fi fi if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE == io ] diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 9983aa0e77..7b9ae09955 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -240,6 +240,11 @@ then fi fi + if [ $OUTPUT_MODE == ardrone ] + then + set FMU_MODE gpio_serial + fi + if [ $HIL == yes ] then set OUTPUT_MODE hil @@ -277,7 +282,7 @@ then tone_alarm $TUNE_OUT_ERROR fi fi - if [ $OUTPUT_MODE == fmu ] + if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE = ardrone ] then echo "[init] Use FMU PWM as primary output" if fmu mode_$FMU_MODE @@ -351,7 +356,7 @@ then fi fi else - if [ $OUTPUT_MODE != fmu ] + if [ $OUTPUT_MODE != fmu -a $OUTPUT_MODE != ardrone ] then if fmu mode_$FMU_MODE then @@ -387,7 +392,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes -o $ARDRONE == yes ] + if [ $TTYS1_BUSY == yes -o $OUTPUT_MODE == ardrone ] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0 @@ -430,7 +435,7 @@ then # # Start up ARDrone Motor interface # - if [ $ARDRONE == yes ] + if [ $OUTPUT_MODE == ardrone ] then ardrone_interface start -d /dev/ttyS1 fi From 25faf1b8f8716323233d6f966aac65e0c9e8d61a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 6 Mar 2014 17:44:10 +0400 Subject: [PATCH 76/76] ardrone: minor fixes --- ROMFS/px4fmu_common/init.d/4008_ardrone | 2 +- ROMFS/px4fmu_common/init.d/rcS | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index 39fe66234b..0f98f7b6c2 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -32,4 +32,4 @@ fi set OUTPUT_MODE ardrone set USE_IO no -set MIXER skip \ No newline at end of file +set MIXER skip diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 7b9ae09955..b1cd919f72 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -284,7 +284,7 @@ then fi if [ $OUTPUT_MODE == fmu -o $OUTPUT_MODE = ardrone ] then - echo "[init] Use FMU PWM as primary output" + echo "[init] Use FMU as primary output" if fmu mode_$FMU_MODE then echo "[init] FMU mode_$FMU_MODE started" @@ -299,7 +299,7 @@ then then set TTYS1_BUSY yes fi - if [ $FMU_MODE == pwm_gpio ] + if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ] then set TTYS1_BUSY yes fi @@ -372,7 +372,7 @@ then then set TTYS1_BUSY yes fi - if [ $FMU_MODE == pwm_gpio ] + if [ $FMU_MODE == pwm_gpio -o $OUTPUT_MODE == ardrone ] then set TTYS1_BUSY yes fi @@ -392,7 +392,7 @@ then mavlink start -b 230400 -d /dev/ttyACM0 usleep 5000 else - if [ $TTYS1_BUSY == yes -o $OUTPUT_MODE == ardrone ] + if [ $TTYS1_BUSY == yes ] then # Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else mavlink start -d /dev/ttyS0