aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-03-06 21:53:51 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-03-06 21:53:51 +0100
commitb086bdf21ef593331da8c48cc21468ff823cdc01 (patch)
tree85bf8eb5d3c2c62a2252f5d6a4ebe7bf982daaf5 /src/modules
parentf2b46389ee8c8e9dd73ad9ac1fc8170c759e8b1c (diff)
parent320745003783c6306996a1e6339ec91bfefcc7d0 (diff)
downloadpx4-firmware-b086bdf21ef593331da8c48cc21468ff823cdc01.tar.gz
px4-firmware-b086bdf21ef593331da8c48cc21468ff823cdc01.tar.bz2
px4-firmware-b086bdf21ef593331da8c48cc21468ff823cdc01.zip
Merge remote-tracking branch 'upstream/master' into launchdetector
Conflicts: src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp2
-rw-r--r--src/modules/commander/airspeed_calibration.cpp2
-rw-r--r--src/modules/commander/commander.cpp82
-rw-r--r--src/modules/commander/commander_helper.cpp91
-rw-r--r--src/modules/commander/commander_helper.h14
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp134
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c7
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp61
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp5
-rw-r--r--src/modules/navigator/navigator_main.cpp144
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c26
-rw-r--r--src/modules/px4iofirmware/dsm.c34
-rw-r--r--src/modules/px4iofirmware/mixer.cpp2
-rw-r--r--src/modules/px4iofirmware/registers.c2
-rw-r--r--src/modules/sdlog2/logbuffer.c3
-rw-r--r--src/modules/sdlog2/sdlog2.c3
-rw-r--r--src/modules/systemlib/perf_counter.h2
17 files changed, 322 insertions, 292 deletions
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 36b75dd58..1cbdf9bf8 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 1809f9688..6039d92a7 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 6d14472f3..d114a2e5c 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -610,7 +610,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 */
@@ -902,11 +901,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 (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");
+ }
+ }
}
/* update global position estimate */
@@ -961,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;
@@ -1024,14 +1025,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);
@@ -1105,7 +1104,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);
}
}
@@ -1200,8 +1199,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 */
@@ -1257,7 +1257,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 && parachute_enabled && 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);
}
}
@@ -1312,26 +1312,23 @@ 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;
-
- } 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_ARMING_WARNING_TUNE);
+ arm_tune_played = true;
} 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();
- battery_tune_played = false;
+ } 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 {
+ set_tune(TONE_STOP_TUNE);
}
/* 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;
}
@@ -1426,11 +1423,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 {
@@ -1697,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);
}
}
@@ -1719,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);
}
}
@@ -1727,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:
@@ -1887,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 033e7dc88..fe6c9bfaa 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -45,6 +45,7 @@
#include <stdbool.h>
#include <fcntl.h>
#include <math.h>
+#include <string.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
@@ -81,11 +82,22 @@ bool is_rotary_wing(const struct vehicle_status_s *current_status)
|| (current_status->system_type == VEHICLE_TYPE_COAXIAL);
}
-static int buzzer;
-static hrt_abstime blink_msg_end;
+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 = 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] = 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);
if (buzzer < 0) {
@@ -101,58 +113,60 @@ void buzzer_deinit()
close(buzzer);
}
-void tune_error()
-{
- ioctl(buzzer, TONE_SET_ALARM, TONE_ERROR_TUNE);
+void set_tune(int 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) {
+ /* 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_buzzer == 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_buzzer == 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);
-}
-
-void tune_negative()
-{
- led_negative();
- ioctl(buzzer, TONE_SET_ALARM, TONE_NOTIFY_NEGATIVE_TUNE);
+ if (use_buzzer) {
+ set_tune(TONE_NOTIFY_NEUTRAL_TUNE);
+ }
}
-void led_negative()
+/**
+ * Blink red LED and play negative tune (if use_buzzer == 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()
@@ -161,6 +175,7 @@ int blink_msg_state()
return 0;
} else if (hrt_absolute_time() > blink_msg_end) {
+ blink_msg_end = 0;
return 2;
} else {
@@ -168,8 +183,8 @@ int blink_msg_state()
}
}
-static int leds;
-static int rgbleds;
+static int leds = -1;
+static int rgbleds = -1;
int led_init()
{
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
index af25a5e97..e75f2592f 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();
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 ab2a2439b..774758ef4 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 */
@@ -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;
@@ -194,7 +194,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;
@@ -235,7 +235,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;
@@ -280,7 +279,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;
@@ -374,6 +372,7 @@ FixedwingPositionControl *g_control;
FixedwingPositionControl::FixedwingPositionControl() :
+ _mavlink_fd(-1),
_task_should_exit(false),
_control_task(-1),
@@ -392,39 +391,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),
+ last_manual(false),
usePreTakeoffThrust(false),
- last_manual(false)
+ flare_curve_alt_last(0.0f),
+ launchDetector(),
+ _airspeed_error(0.0f),
+ _airspeed_valid(false),
+ _groundspeed_undershoot(0.0f),
+ _global_pos_valid(false),
+ _att(),
+ _att_sp(),
+ _nav_capabilities(),
+ _manual(),
+ _airspeed(),
+ _control_mode(),
+ _global_pos(),
+ _pos_sp_triplet(),
+ _sensor_combined()
{
- /* 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};
-
-
-
-
_nav_capabilities.turn_distance = 0.0f;
_parameter_handles.l1_period = param_find("FW_L1_PERIOD");
@@ -444,7 +438,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");
@@ -533,7 +526,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));
@@ -600,8 +592,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;
+ _launch_lon = _global_pos.lon;
_launch_alt = _global_pos.alt;
_launch_valid = true;
}
@@ -716,7 +708,7 @@ void
FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector<2> &current_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));
@@ -902,8 +894,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_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;
+ /* 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);
@@ -929,7 +923,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_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;
@@ -948,38 +942,24 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_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);
- //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),
@@ -1082,13 +1062,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_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 */
@@ -1307,7 +1289,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;
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 62a340e90..0909135e1 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
@@ -349,13 +349,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);
-
-/**
*
*
* @group L1 Control
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 38fde0cac..9cb8e8344 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 <stdlib.h>
#include <string.h>
#include <unistd.h>
-#include <fcntl.h>
#include <errno.h>
#include <math.h>
#include <poll.h>
-#include <time.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
@@ -71,7 +69,6 @@
#include <uORB/topics/parameter_update.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
-#include <systemlib/pid/pid.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
@@ -84,8 +81,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 +132,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,13 +257,15 @@ 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));
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();
@@ -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,18 @@ 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 +558,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 +598,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 +614,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 +656,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;
@@ -695,9 +693,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();
@@ -767,10 +762,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) {
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 25d34c872..78d06ba5b 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 <errno.h>
#include <math.h>
#include <poll.h>
-#include <time.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
#include <uORB/uORB.h>
@@ -68,7 +67,6 @@
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
-#include <systemlib/pid/pid.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
#include <lib/geo/geo.h>
@@ -732,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);
@@ -794,7 +791,6 @@ MulticopterPositionControl::task_main()
}
thrust_int(2) = -i;
- mavlink_log_info(_mavlink_fd, "[mpc] reset hovering thrust: %.2f", (double)i);
}
} else {
@@ -806,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 {
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 577c767a8..16eca8d79 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;
@@ -322,6 +322,11 @@ private:
bool onboard_mission_available(unsigned relative_index);
/**
+ * Reset all "reached" flags.
+ */
+ void reset_reached();
+
+ /**
* Check if current mission item has been reached.
*/
bool check_mission_item_reached();
@@ -382,11 +387,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 +400,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");
@@ -695,7 +700,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);
}
@@ -741,7 +746,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);
}
@@ -749,9 +754,7 @@ Navigator::task_main()
break;
case NAV_STATE_LAND:
- if (myState != NAV_STATE_READY) {
- dispatch(EVENT_LAND_REQUESTED);
- }
+ dispatch(EVENT_LAND_REQUESTED);
break;
@@ -853,11 +856,8 @@ 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: navigation state: %s", nav_states_str[myState]);
prevState = myState;
-
- /* reset time counter on state changes */
- _time_first_inside_orbit = 0;
}
perf_end(_loop_perf);
@@ -955,7 +955,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},
@@ -1009,6 +1009,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 +1026,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 +1050,8 @@ Navigator::start_ready()
void
Navigator::start_loiter()
{
+ reset_reached();
+
_do_takeoff = false;
/* set loiter position if needed */
@@ -1061,11 +1067,11 @@ Navigator::start_loiter()
/* use current altitude if above min altitude set by parameter */
if (_global_pos.alt < min_alt_amsl && !_vstatus.is_rotary_wing) {
_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: 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: loiter at current altitude");
}
}
@@ -1091,6 +1097,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 +1112,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);
@@ -1162,14 +1167,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: takeoff to %.1fm above home", (double)(_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: 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: heading to offboard WP %d", index);
}
}
@@ -1224,6 +1229,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 +1262,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 +1294,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: {
@@ -1318,7 +1326,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: RTL: climb to %.1fm above home", (double)(climb_alt - _home_pos.alt));
break;
}
@@ -1330,7 +1338,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;
@@ -1344,7 +1359,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: RTL: return at %.1fm above home", (double)(_mission_item.altitude - _home_pos.alt));
break;
}
@@ -1362,7 +1377,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,12 +1386,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: RTL: descend to %.1fm above home", (double)(_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;
}
@@ -1388,7 +1403,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 {
@@ -1418,17 +1434,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;
@@ -1505,7 +1532,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);
@@ -1525,16 +1552,14 @@ 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: waypoint reached, wait for %.1fs", (double)_mission_item.time_inside);
}
}
/* 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;
}
}
@@ -1544,13 +1569,22 @@ 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()
{
if (myState == NAV_STATE_MISSION) {
if (_do_takeoff) {
/* takeoff completed */
_do_takeoff = false;
- mavlink_log_info(_mavlink_fd, "[navigator] takeoff completed");
+ mavlink_log_info(_mavlink_fd, "#audio: takeoff completed");
} else {
/* advance by one mission item */
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 bf4f7ae97..d6d03367b 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 <stdio.h>
#include <stdbool.h>
#include <fcntl.h>
-#include <float.h>
#include <string.h>
#include <nuttx/config.h>
#include <nuttx/sched.h>
#include <sys/prctl.h>
#include <termios.h>
-#include <errno.h>
-#include <limits.h>
#include <math.h>
#include <uORB/uORB.h>
#include <uORB/topics/parameter_update.h>
@@ -170,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);
}
@@ -711,6 +709,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);
@@ -718,7 +721,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 */
@@ -742,7 +746,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));
}
}
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index 60eda2319..d3f365822 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
@@ -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;
@@ -368,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 = ((((int)value - 1024) * 1000) / 1700) + 1500;
/*
* Store the decoded channel into the R/C input buffer, taking into
@@ -400,6 +415,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;
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index f39fcf7ec..6a4429461 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))
)
);
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 1335f52e1..97d25bbfa 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:
diff --git a/src/modules/sdlog2/logbuffer.c b/src/modules/sdlog2/logbuffer.c
index b3243f7b5..6a29d7e5c 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 <anton.babushkin@me.com>
+ * 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 68e6a7469..1365d9e70 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 <lm@inf.ethz.ch>
- * Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -451,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;
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index e1e3cbe95..d8f69fdbf 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 <stdint.h>
+
/**
* Counter types.
*/