From 708ee8ae3aa4d4d5eac9e2fd86ed9673c126fe33 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 22 Aug 2014 20:30:06 +0200 Subject: autolaunch: added param for delay --- src/lib/launchdetection/CatapultLaunchMethod.cpp | 19 ++++++++++++++++--- src/lib/launchdetection/CatapultLaunchMethod.h | 4 ++++ src/lib/launchdetection/launchdetection_params.c | 9 +++++++++ 3 files changed, 29 insertions(+), 3 deletions(-) (limited to 'src') diff --git a/src/lib/launchdetection/CatapultLaunchMethod.cpp b/src/lib/launchdetection/CatapultLaunchMethod.cpp index c555a0a69..c4425bbe0 100644 --- a/src/lib/launchdetection/CatapultLaunchMethod.cpp +++ b/src/lib/launchdetection/CatapultLaunchMethod.cpp @@ -51,7 +51,8 @@ CatapultLaunchMethod::CatapultLaunchMethod(SuperBlock *parent) : integrator(0.0f), launchDetected(false), threshold_accel(this, "A"), - threshold_time(this, "T") + threshold_time(this, "T"), + delay(this, "DELAY") { } @@ -78,21 +79,33 @@ void CatapultLaunchMethod::update(float accel_x) // (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt); /* reset integrator */ integrator = 0.0f; - launchDetected = false; + } + + if (launchDetected) { + delayCounter += dt; + if (delayCounter > delay.get()) { + delayPassed = true; + } } } bool CatapultLaunchMethod::getLaunchDetected() { - return launchDetected; + if (delay.get() > 0.0f) { + return delayPassed; + } else { + return launchDetected; + } } void CatapultLaunchMethod::reset() { integrator = 0.0f; + delayCounter = 0.0f; launchDetected = false; + delayPassed = false; } } diff --git a/src/lib/launchdetection/CatapultLaunchMethod.h b/src/lib/launchdetection/CatapultLaunchMethod.h index 23757f6f3..a64d482f6 100644 --- a/src/lib/launchdetection/CatapultLaunchMethod.h +++ b/src/lib/launchdetection/CatapultLaunchMethod.h @@ -63,10 +63,14 @@ public: private: hrt_abstime last_timestamp; float integrator; + float delayCounter; + bool launchDetected; + bool delayPassed; control::BlockParamFloat threshold_accel; control::BlockParamFloat threshold_time; + control::BlockParamFloat delay; }; diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c index 8df8c696c..02f01bc66 100644 --- a/src/lib/launchdetection/launchdetection_params.c +++ b/src/lib/launchdetection/launchdetection_params.c @@ -77,6 +77,15 @@ PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f); */ PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f); +/** + * Catapult delay + * + * + * + * @min 0 + * @group Launch detection + */ +PARAM_DEFINE_FLOAT(LAUN_CAT_DELAY, 0.0f); /** * Throttle setting while detecting launch. * -- cgit v1.2.3 From 5a5617cb597b16b789a6fa175410d667f45cf907 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 23 Aug 2014 11:42:53 +0200 Subject: launchdetector: return state of detection The launchdetector now has a intermediate state (controlsenabled) which is meant to be interpreted by the controller as: "perform attitude control but do not yet power up the motor". This can be used in the floating phase during a bungee launch for example. --- src/lib/launchdetection/CatapultLaunchMethod.cpp | 70 ++++++++++++++---------- src/lib/launchdetection/CatapultLaunchMethod.h | 13 ++--- src/lib/launchdetection/LaunchDetector.cpp | 27 +++++++-- src/lib/launchdetection/LaunchDetector.h | 8 ++- src/lib/launchdetection/LaunchMethod.h | 13 ++++- src/lib/launchdetection/launchdetection_params.c | 8 ++- 6 files changed, 91 insertions(+), 48 deletions(-) (limited to 'src') diff --git a/src/lib/launchdetection/CatapultLaunchMethod.cpp b/src/lib/launchdetection/CatapultLaunchMethod.cpp index 2b876b629..65ae461db 100644 --- a/src/lib/launchdetection/CatapultLaunchMethod.cpp +++ b/src/lib/launchdetection/CatapultLaunchMethod.cpp @@ -49,10 +49,10 @@ CatapultLaunchMethod::CatapultLaunchMethod(SuperBlock *parent) : SuperBlock(parent, "CAT"), last_timestamp(hrt_absolute_time()), integrator(0.0f), - launchDetected(false), - threshold_accel(this, "A"), - threshold_time(this, "T"), - delay(this, "DELAY") + state(LAUNCHDETECTION_RES_NONE), + thresholdAccel(this, "A"), + thresholdTime(this, "T"), + motorDelay(this, "MDEL") { } @@ -66,46 +66,56 @@ void CatapultLaunchMethod::update(float accel_x) float dt = (float)hrt_elapsed_time(&last_timestamp) * 1e-6f; last_timestamp = hrt_absolute_time(); - if (accel_x > threshold_accel.get()) { - integrator += dt; -// warnx("*** integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f", -// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt); - if (integrator > threshold_time.get()) { - launchDetected = true; + switch (state) { + case LAUNCHDETECTION_RES_NONE: + /* Detect a acceleration that is longer and stronger as the minimum given by the params */ + if (accel_x > thresholdAccel.get()) { + integrator += dt; + if (integrator > thresholdTime.get()) { + if (motorDelay.get() > 0.0f) { + state = LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL; + warnx("Launch detected: state: enablecontrol, waiting %.2fs until using full" + " throttle", (double)motorDelay.get()); + } else { + /* No motor delay set: go directly to enablemotors state */ + state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS; + warnx("Launch detected: state: enablemotors (delay not activated)"); + } + } + } else { + /* reset */ + reset(); } + break; + + case LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL: + /* Vehicle is currently controlling attitude but not with full throttle. Waiting undtil delay is + * over to allow full throttle */ + motorDelayCounter += dt; + if (motorDelayCounter > motorDelay.get()) { + warnx("Launch detected: state enablemotors"); + state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS; + } + break; - } else { -// warnx("integrator %.3f, threshold_accel %.3f, threshold_time %.3f, accel_x %.3f, dt %.3f", -// (double)integrator, (double)threshold_accel.get(), (double)threshold_time.get(), (double)accel_x, (double)dt); - /* reset integrator */ - integrator = 0.0f; - } + default: + break; - if (launchDetected) { - delayCounter += dt; - if (delayCounter > delay.get()) { - delayPassed = true; - } } } -bool CatapultLaunchMethod::getLaunchDetected() +LaunchDetectionResult CatapultLaunchMethod::getLaunchDetected() const { - if (delay.get() > 0.0f) { - return delayPassed; - } else { - return launchDetected; - } + return state; } void CatapultLaunchMethod::reset() { integrator = 0.0f; - delayCounter = 0.0f; - launchDetected = false; - delayPassed = false; + motorDelayCounter = 0.0f; + state = LAUNCHDETECTION_RES_NONE; } } diff --git a/src/lib/launchdetection/CatapultLaunchMethod.h b/src/lib/launchdetection/CatapultLaunchMethod.h index a64d482f6..d918c3a76 100644 --- a/src/lib/launchdetection/CatapultLaunchMethod.h +++ b/src/lib/launchdetection/CatapultLaunchMethod.h @@ -57,20 +57,19 @@ public: ~CatapultLaunchMethod(); void update(float accel_x); - bool getLaunchDetected(); + LaunchDetectionResult getLaunchDetected() const; void reset(); private: hrt_abstime last_timestamp; float integrator; - float delayCounter; + float motorDelayCounter; - bool launchDetected; - bool delayPassed; + LaunchDetectionResult state; - control::BlockParamFloat threshold_accel; - control::BlockParamFloat threshold_time; - control::BlockParamFloat delay; + control::BlockParamFloat thresholdAccel; + control::BlockParamFloat thresholdTime; + control::BlockParamFloat motorDelay; }; diff --git a/src/lib/launchdetection/LaunchDetector.cpp b/src/lib/launchdetection/LaunchDetector.cpp index 3bf47bbb0..2958c0a31 100644 --- a/src/lib/launchdetection/LaunchDetector.cpp +++ b/src/lib/launchdetection/LaunchDetector.cpp @@ -46,6 +46,7 @@ namespace launchdetection LaunchDetector::LaunchDetector() : SuperBlock(NULL, "LAUN"), + activeLaunchDetectionMethodIndex(-1), launchdetection_on(this, "ALL_ON"), throttlePreTakeoff(this, "THR_PRE") { @@ -65,7 +66,14 @@ LaunchDetector::~LaunchDetector() void LaunchDetector::reset() { /* Reset all detectors */ - launchMethods[0]->reset(); + for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) { + launchMethods[i]->reset(); + } + + /* Reset active launchdetector */ + activeLaunchDetectionMethodIndex = -1; + + } void LaunchDetector::update(float accel_x) @@ -77,17 +85,24 @@ void LaunchDetector::update(float accel_x) } } -bool LaunchDetector::getLaunchDetected() +LaunchDetectionResult LaunchDetector::getLaunchDetected() { if (launchdetection_on.get() == 1) { - for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) { - if(launchMethods[i]->getLaunchDetected()) { - return true; + if (activeLaunchDetectionMethodIndex < 0) { + /* None of the active launchmethods has detected a launch, check all launchmethods */ + for (uint8_t i = 0; i < sizeof(launchMethods)/sizeof(LaunchMethod); i++) { + if(launchMethods[i]->getLaunchDetected() != LAUNCHDETECTION_RES_NONE) { + warnx("selecting launchmethod %d", i); + activeLaunchDetectionMethodIndex = i; // from now on only check this method + return launchMethods[i]->getLaunchDetected(); + } } + } else { + return launchMethods[activeLaunchDetectionMethodIndex]->getLaunchDetected(); } } - return false; + return LAUNCHDETECTION_RES_NONE; } } diff --git a/src/lib/launchdetection/LaunchDetector.h b/src/lib/launchdetection/LaunchDetector.h index 1a214b66e..b48e724ba 100644 --- a/src/lib/launchdetection/LaunchDetector.h +++ b/src/lib/launchdetection/LaunchDetector.h @@ -59,7 +59,7 @@ public: void reset(); void update(float accel_x); - bool getLaunchDetected(); + LaunchDetectionResult getLaunchDetected(); bool launchDetectionEnabled() { return (bool)launchdetection_on.get(); }; float getThrottlePreTakeoff() {return throttlePreTakeoff.get(); } @@ -67,6 +67,12 @@ public: // virtual bool getLaunchDetected(); protected: private: + int activeLaunchDetectionMethodIndex; /**< holds a index to the launchMethod in the array launchMethods + which detected a Launch. If no launchMethod has detected a launch yet the + value is -1. Once one launchMetthod has detected a launch only this + method is checked for further adavancing in the state machine (e.g. when + to power up the motors) */ + LaunchMethod* launchMethods[1]; control::BlockParamInt launchdetection_on; control::BlockParamFloat throttlePreTakeoff; diff --git a/src/lib/launchdetection/LaunchMethod.h b/src/lib/launchdetection/LaunchMethod.h index e04467f6a..d2f091cea 100644 --- a/src/lib/launchdetection/LaunchMethod.h +++ b/src/lib/launchdetection/LaunchMethod.h @@ -44,11 +44,22 @@ namespace launchdetection { +enum LaunchDetectionResult { + LAUNCHDETECTION_RES_NONE = 0, /**< No launch has been detected */ + LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL = 1, /**< Launch has been detected, the controller should + control the attitude. However any motors should not throttle + up and still be set to 'throttlePreTakeoff'. + For instance this is used to have a delay for the motor + when launching a fixed wing aircraft from a bungee */ + LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS = 2 /**< Launch has been detected, teh controller should control + attitude and also throttle up the motors. */ +}; + class LaunchMethod { public: virtual void update(float accel_x) = 0; - virtual bool getLaunchDetected() = 0; + virtual LaunchDetectionResult getLaunchDetected() const = 0; virtual void reset() = 0; protected: diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c index 02f01bc66..d35eb11f6 100644 --- a/src/lib/launchdetection/launchdetection_params.c +++ b/src/lib/launchdetection/launchdetection_params.c @@ -78,14 +78,16 @@ PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f); PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f); /** - * Catapult delay - * + * Motor delay * + * Delay between starting attitude control and powering up the thorttle (giving throttle control to the controller) + * Before this timespan is up the throttle will be set to LAUN_THR_PRE, set to 0 to deactivate * + * @unit seconds * @min 0 * @group Launch detection */ -PARAM_DEFINE_FLOAT(LAUN_CAT_DELAY, 0.0f); +PARAM_DEFINE_FLOAT(LAUN_CAT_MDEL, 0.0f); /** * Throttle setting while detecting launch. * -- cgit v1.2.3 From 40d47fb069cb60303102f3bfba21f6dc5e0aa5a9 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 23 Aug 2014 11:45:20 +0200 Subject: fw pos control: use new lauchdetector states --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 73 +++++++++++++--------- 1 file changed, 43 insertions(+), 30 deletions(-) (limited to 'src') 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 350ce6dec..6dd458516 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 @@ -102,6 +102,8 @@ static int _control_task = -1; /**< task handle for sensor task */ */ extern "C" __EXPORT int fw_pos_control_l1_main(int argc, char *argv[]); +using namespace launchdetection; + class FixedwingPositionControl { public: @@ -171,7 +173,7 @@ private: bool land_onslope; /* takeoff/launch states */ - bool launch_detected; + LaunchDetectionResult launch_detection_state; bool usePreTakeoffThrust; bool last_manual; ///< true if the last iteration was in manual mode (used to determine when a reset is needed) @@ -438,7 +440,7 @@ FixedwingPositionControl::FixedwingPositionControl() : land_stayonground(false), land_motor_lim(false), land_onslope(false), - launch_detected(false), + launch_detection_state(LAUNCHDETECTION_RES_NONE), usePreTakeoffThrust(false), last_manual(false), landingslope(), @@ -1076,39 +1078,51 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) { /* Perform launch detection */ - 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) { - mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running"); - last_sent = hrt_absolute_time(); - } + if (launchDetector.launchDetectionEnabled() && + launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) { + /* Inform user that launchdetection is running */ + static hrt_abstime last_sent = 0; + if(hrt_absolute_time() - last_sent > 4e6) { + mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running"); + last_sent = hrt_absolute_time(); + } + + /* Detect launch */ + launchDetector.update(_sensor_combined.accelerometer_m_s2[0]); + + /* update our copy of the laucn detection state */ + launch_detection_state = launchDetector.getLaunchDetected(); + /* Depending on launch detection state set control flags */ + if(launch_detection_state == LAUNCHDETECTION_RES_NONE) { /* 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; - mavlink_log_info(_mavlink_fd, "#audio: Takeoff"); - } - } else { - /* no takeoff detection --> fly */ - launch_detected = true; - warnx("launchdetection off"); + usePreTakeoffThrust = true; + } else if (launch_detection_state == LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL) { + usePreTakeoffThrust = true; + } else { + usePreTakeoffThrust = false; } + } else { + /* no takeoff detection --> fly */ + usePreTakeoffThrust = false; + launch_detection_state = LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL; } - _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d); - _att_sp.roll_body = _l1_control.nav_roll(); - _att_sp.yaw_body = _l1_control.nav_bearing(); + if (launch_detection_state != LAUNCHDETECTION_RES_NONE) { + /* Launch has been detected, hence we have to control the plane. The usePreTakeoffThrust + * flag determines how much thrust we apply */ - if (launch_detected) { - usePreTakeoffThrust = false; + _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d); + _att_sp.roll_body = _l1_control.nav_roll(); + _att_sp.yaw_body = _l1_control.nav_bearing(); + + float takeoff_throttle = usePreTakeoffThrust ? launchDetector.getThrottlePreTakeoff() : + _parameters.throttle_max; /* apply minimum pitch and limit roll if target altitude is not within 10 meters */ if (_parameters.climbout_diff > 0.001f && altitude_error > _parameters.climbout_diff) { @@ -1119,7 +1133,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi eas2tas, math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max), - _parameters.throttle_min, _parameters.throttle_max, + _parameters.throttle_min, takeoff_throttle, _parameters.throttle_cruise, true, math::max(math::radians(pos_sp_triplet.current.pitch_min), @@ -1138,17 +1152,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max), _parameters.throttle_min, - _parameters.throttle_max, + takeoff_throttle, _parameters.throttle_cruise, false, math::radians(_parameters.pitch_limit_min), _global_pos.alt, ground_speed); } - - } else { - usePreTakeoffThrust = true; } + } /* reset landing state */ @@ -1182,6 +1194,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } } + /* making sure again that the correct thrust is used, without depending on library calls */ if (usePreTakeoffThrust) { _att_sp.thrust = launchDetector.getThrottlePreTakeoff(); } @@ -1342,7 +1355,7 @@ FixedwingPositionControl::task_main() void FixedwingPositionControl::reset_takeoff_state() { - launch_detected = false; + launch_detection_state = LAUNCHDETECTION_RES_NONE; usePreTakeoffThrust = false; launchDetector.reset(); } -- cgit v1.2.3 From 9f5004be2d282a0bb8f2618545d0c6174df2e29a Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 23 Aug 2014 12:13:30 +0200 Subject: fw pos control: set default roll, pitch while waiting for launch --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) (limited to 'src') 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 6dd458516..9cbe5483b 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 @@ -1143,7 +1143,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi TECS_MODE_TAKEOFF); /* limit roll motion to ensure enough lift */ - _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f)); + _att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), + math::radians(15.0f)); } else { tecs_update_pitch_throttle(_pos_sp_triplet.current.alt, @@ -1159,6 +1160,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi _global_pos.alt, ground_speed); } + } else { + /* Set default roll and pitch setpoints during detection phase */ + _att_sp.roll_body = 0.0f; + _att_sp.pitch_body = math::max(math::radians(pos_sp_triplet.current.pitch_min), + math::radians(10.0f)); } } -- cgit v1.2.3 From cfbbe60291028c60a5dd0a8f2b8bad265a7ee839 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 23 Aug 2014 12:41:48 +0200 Subject: fw pos control: launchdetection logic cleanup --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 44 +++++++++------------- 1 file changed, 18 insertions(+), 26 deletions(-) (limited to 'src') 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 9cbe5483b..da81b0dba 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 @@ -174,7 +174,6 @@ private: /* takeoff/launch states */ LaunchDetectionResult launch_detection_state; - bool usePreTakeoffThrust; bool last_manual; ///< true if the last iteration was in manual mode (used to determine when a reset is needed) @@ -441,7 +440,6 @@ FixedwingPositionControl::FixedwingPositionControl() : land_motor_lim(false), land_onslope(false), launch_detection_state(LAUNCHDETECTION_RES_NONE), - usePreTakeoffThrust(false), last_manual(false), landingslope(), flare_curve_alt_rel_last(0.0f), @@ -1092,37 +1090,24 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi /* update our copy of the laucn detection state */ launch_detection_state = launchDetector.getLaunchDetected(); - - /* Depending on launch detection state set control flags */ - if(launch_detection_state == LAUNCHDETECTION_RES_NONE) { - /* 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; - - usePreTakeoffThrust = true; - } else if (launch_detection_state == LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL) { - usePreTakeoffThrust = true; - } else { - usePreTakeoffThrust = false; - } } else { /* no takeoff detection --> fly */ - usePreTakeoffThrust = false; - launch_detection_state = LAUNCHDETECTION_RES_DETECTED_ENABLECONTROL; + launch_detection_state = LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS; } + /* Set control values depending on the detection state */ if (launch_detection_state != LAUNCHDETECTION_RES_NONE) { - /* Launch has been detected, hence we have to control the plane. The usePreTakeoffThrust - * flag determines how much thrust we apply */ + /* Launch has been detected, hence we have to control the plane. */ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d); _att_sp.roll_body = _l1_control.nav_roll(); _att_sp.yaw_body = _l1_control.nav_bearing(); - float takeoff_throttle = usePreTakeoffThrust ? launchDetector.getThrottlePreTakeoff() : - _parameters.throttle_max; + /* Select throttle: only in LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS we want to use + * full throttle, otherwise we use the preTakeOff Throttle */ + float takeoff_throttle = launch_detection_state != + LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS ? + launchDetector.getThrottlePreTakeoff() : _parameters.throttle_max; /* apply minimum pitch and limit roll if target altitude is not within 10 meters */ if (_parameters.climbout_diff > 0.001f && altitude_error > _parameters.climbout_diff) { @@ -1161,6 +1146,12 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi ground_speed); } } else { + /* 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; + /* Set default roll and pitch setpoints during detection phase */ _att_sp.roll_body = 0.0f; _att_sp.pitch_body = math::max(math::radians(pos_sp_triplet.current.pitch_min), @@ -1200,8 +1191,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } } - /* making sure again that the correct thrust is used, without depending on library calls */ - if (usePreTakeoffThrust) { + /* Copy thrust and pitch values from tecs + * making sure again that the correct thrust is used, without depending on library calls */ + if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF && + launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) { _att_sp.thrust = launchDetector.getThrottlePreTakeoff(); } else { @@ -1362,7 +1355,6 @@ FixedwingPositionControl::task_main() void FixedwingPositionControl::reset_takeoff_state() { launch_detection_state = LAUNCHDETECTION_RES_NONE; - usePreTakeoffThrust = false; launchDetector.reset(); } -- cgit v1.2.3 From c591444c1e2e4124d28a03653c0ccdbcd305c1c2 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 25 Aug 2014 12:48:14 +0200 Subject: fw pos control: set pitch sp correctly while waiting for launch --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) (limited to 'src') 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 da81b0dba..b3a78ad82 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 @@ -1192,7 +1192,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } /* Copy thrust and pitch values from tecs - * making sure again that the correct thrust is used, without depending on library calls */ + * making sure again that the correct thrust is used, + * without depending on library calls */ if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF && launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) { _att_sp.thrust = launchDetector.getThrottlePreTakeoff(); @@ -1200,7 +1201,12 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi else { _att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : _tecs.get_throttle_demand(), throttle_max); } - _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand(); + /* During a takeoff waypoint while waiting for launch the pitch sp is set + * already (not by tecs) */ + if (!(pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF && + launch_detection_state == LAUNCHDETECTION_RES_NONE)) { + _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand(); + } if (_control_mode.flag_control_position_enabled) { last_manual = false; -- cgit v1.2.3