aboutsummaryrefslogtreecommitdiff
path: root/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-06-27 14:39:36 +0200
committerJulian Oes <julian@oes.ch>2014-06-27 14:39:36 +0200
commitcc8f7f4c97de923f60f9469aa2847e6e1474d52d (patch)
tree4a5895a4421fbd66a2159de08c3ad70506b55051 /src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
parent3aab37e0e04ce98ddacd99e238e626ab5c3d4445 (diff)
parentf3a77705a701a92ae510e18280136b3b7f204b3e (diff)
downloadpx4-firmware-cc8f7f4c97de923f60f9469aa2847e6e1474d52d.tar.gz
px4-firmware-cc8f7f4c97de923f60f9469aa2847e6e1474d52d.tar.bz2
px4-firmware-cc8f7f4c97de923f60f9469aa2847e6e1474d52d.zip
Merge branch 'master' into navigator_rewrite
Conflicts: src/modules/commander/commander.cpp src/modules/commander/state_machine_helper.h src/modules/mavlink/mavlink_messages.cpp
Diffstat (limited to 'src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp14
1 files changed, 12 insertions, 2 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 1bb955173..49d812e7e 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
@@ -872,6 +872,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* current waypoint (the one currently heading for) */
math::Vector<2> curr_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon);
+ /* Initialize attitude controller integrator reset flags to 0 */
+ _att_sp.roll_reset_integral = false;
+ _att_sp.pitch_reset_integral = false;
+ _att_sp.yaw_reset_integral = false;
/* previous waypoint */
math::Vector<2> prev_wp;
@@ -1061,15 +1065,21 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) {
/* Perform launch detection */
-// warnx("Launch detection running");
if(!launch_detected) { //do not do further checks once a launch was detected
if (launchDetector.launchDetectionEnabled()) {
static hrt_abstime last_sent = 0;
if(hrt_absolute_time() - last_sent > 4e6) {
-// warnx("Launch detection running");
mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
last_sent = hrt_absolute_time();
}
+
+ /* Tell the attitude controller to stop integrating while we are waiting
+ * for the launch */
+ _att_sp.roll_reset_integral = true;
+ _att_sp.pitch_reset_integral = true;
+ _att_sp.yaw_reset_integral = true;
+
+ /* Detect launch */
launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
if (launchDetector.getLaunchDetected()) {
launch_detected = true;