From 876f8eca1dd32b96e867c36e94da5b9247e4fd1f Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 21 May 2015 20:39:09 +0200 Subject: [PATCH 01/58] OP-1900 New settings for autotakeoff/autoland added --- .../uavobjectdefinition/fixedwingpathfollowersettings.xml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml index 8a7e5d064..230eebbc8 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -50,6 +50,14 @@ + + + + + + + From aac9159e87bec443c6905c90aed39ea6fcd8c860 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 00:32:08 +0200 Subject: [PATCH 02/58] OP-1900 OP-1054 Autotakeoff and Land controllers for fixed wing --- flight/libraries/paths.c | 1 + .../fixedwingautotakeoffcontroller.cpp | 251 ++++++++++++++++++ .../PathFollower/fixedwingflycontroller.cpp | 17 -- .../PathFollower/fixedwinglandcontroller.cpp | 143 ++++++++++ .../inc/fixedwingautotakeoffcontroller.h | 87 ++++++ .../PathFollower/inc/fixedwingflycontroller.h | 13 +- .../inc/fixedwinglandcontroller.h | 66 +++++ flight/modules/PathFollower/pathfollower.cpp | 13 + 8 files changed, 568 insertions(+), 23 deletions(-) create mode 100644 flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp create mode 100644 flight/modules/PathFollower/fixedwinglandcontroller.cpp create mode 100644 flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h create mode 100644 flight/modules/PathFollower/inc/fixedwinglandcontroller.h diff --git a/flight/libraries/paths.c b/flight/libraries/paths.c index 8656b920a..620493792 100644 --- a/flight/libraries/paths.c +++ b/flight/libraries/paths.c @@ -61,6 +61,7 @@ void path_progress(PathDesiredData *path, float *cur_point, struct path_status * break; case PATHDESIRED_MODE_GOTOENDPOINT: + case PATHDESIRED_MODE_AUTOTAKEOFF: // needed for pos hold at end of takeoff return path_endpoint(path, cur_point, status, mode3D); break; diff --git a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp new file mode 100644 index 000000000..437920d8f --- /dev/null +++ b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp @@ -0,0 +1,251 @@ +/* + ****************************************************************************** + * + * @file FixedWingAutoTakeoffController.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @brief Fixed wing fly controller implementation + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +extern "C" { +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +} + +// C++ includes +#include "fixedwingautotakeoffcontroller.h" + +// Private constants + +// Called when mode first engaged +void FixedWingAutoTakeoffController::Activate(void) +{ + if (!mActive) { + setState(FW_AUTOTAKEOFF_STATE_LAUNCH); + } + FixedWingFlyController::Activate(); +} + +/** + * fixed wing autopilot + * use fixed attitude heading towards destination waypoint + */ +void FixedWingAutoTakeoffController::UpdateAutoPilot() +{ + if (state < FW_AUTOTAKEOFF_STATE_SIZE) { + (this->*runFunctionTable[state])(); + } else { + setState(FW_AUTOTAKEOFF_STATE_LAUNCH); + } +} + +/** + * getAirspeed helper function + */ +float FixedWingAutoTakeoffController::getAirspeed(void) +{ + VelocityStateData v; + float yaw; + + VelocityStateGet(&v); + AttitudeStateYawGet(&yaw); + + // current ground speed projected in forward direction + float groundspeedProjection = v.North * cos_lookup_deg(yaw) + v.East * sin_lookup_deg(yaw); + + // note that airspeedStateBias is ( calibratedAirspeed - groundspeedProjection ) at the time of measurement, + // but thanks to accelerometers, groundspeedProjection reacts faster to changes in direction + // than airspeed and gps sensors alone + return groundspeedProjection + indicatedAirspeedStateBias; +} + + +/** + * setState - state transition including initialization + */ +void FixedWingAutoTakeoffController::setState(FixedWingAutoTakeoffControllerState_T setstate) +{ + if (state < FW_AUTOTAKEOFF_STATE_SIZE && setstate != state) { + state = setstate; + (this->*initFunctionTable[state])(); + } +} + +/** + * setAttitude - output function to steer plane + */ +void FixedWingAutoTakeoffController::setAttitude(bool unsafe) +{ + StabilizationDesiredData stabDesired; + + stabDesired.Roll = 0.0f; + stabDesired.Yaw = initYaw; + if (unsafe) { + stabDesired.Pitch = fixedWingSettings->LandingPitch; + stabDesired.Thrust = 0.0f; + } else { + stabDesired.Pitch = fixedWingSettings->TakeOffPitch; + stabDesired.Thrust = fixedWingSettings->ThrustLimit.Max; + } + stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL; + + StabilizationDesiredSet(&stabDesired); + if (unsafe) { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_WARNING); + } else { + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_OK); + } + + PathStatusSet(pathStatus); +} + +/** + * check if situation is unsafe + */ +bool FixedWingAutoTakeoffController::isUnsafe(void) +{ + bool abort = false; + float speed = getAirspeed(); + + if (speed > maxVelocity) { + maxVelocity = speed; + } + AttitudeStateData attitude; + AttitudeStateGet(&attitude); + // too much bank angle + if (fabsf(attitude.Roll) > fixedWingSettings->TakeOffLimits.RollDeg) { + abort = true; + } + if (fabsf(attitude.Pitch - fixedWingSettings->TakeOffPitch) > fixedWingSettings->TakeOffLimits.PitchDeg) { + abort = true; + } + float deltayaw = attitude.Yaw - initYaw; + if (deltayaw > 180.0f) { + deltayaw -= 360.0f; + } + if (deltayaw < -180.0f) { + deltayaw += 360.0f; + } + if (fabsf(deltayaw) > fixedWingSettings->TakeOffLimits.YawDeg) { + abort = true; + } + return abort; +} + + +// init inactive does nothing +void FixedWingAutoTakeoffController::init_inactive(void) {} + +// init launch resets private variables to start values +void FixedWingAutoTakeoffController::init_launch(void) +{ + // find out vector direction of *runway* (if any) + // and align, otherwise just stay straight ahead + if (fabsf(pathDesired->Start.North - pathDesired->End.North) < 1e-3f && + fabsf(pathDesired->Start.East - pathDesired->End.East) < 1e-3f) { + AttitudeStateYawGet(&initYaw); + } else { + initYaw = RAD2DEG(atan2f(pathDesired->End.East - pathDesired->Start.East, pathDesired->End.North - pathDesired->Start.North)); + if (initYaw < -180.0f) { + initYaw += 360.0f; + } + if (initYaw > 180.0f) { + initYaw -= 360.0f; + } + } + + maxVelocity = getAirspeed(); +} + +// init climb does nothing +void FixedWingAutoTakeoffController::init_climb(void) {} + +// init hold does nothing +void FixedWingAutoTakeoffController::init_hold(void) {} + +// init abort does nothing +void FixedWingAutoTakeoffController::init_abort(void) {} + + +// run inactive does nothing +// no state transitions +void FixedWingAutoTakeoffController::run_inactive(void) {} + +// run launch tries to takeoff - indicates safe situation with engine power (for hand launch) +// run launch checks for: +// 1. min velocity for climb +void FixedWingAutoTakeoffController::run_launch(void) +{ + // state transition + if (maxVelocity > fixedWingSettings->TakeOffLimits.MaxDecelerationDeltaMPS) { + setState(FW_AUTOTAKEOFF_STATE_CLIMB); + } + + setAttitude(isUnsafe()); +} + +// run climb climbs with max power +// run climb checks for: +// 1. min altitude for hold +// 2. critical situation for abort (different than launch) +void FixedWingAutoTakeoffController::run_climb(void) +{ + bool unsafe = isUnsafe(); + float downPos; + + PositionStateDownGet(&downPos); + + if (unsafe) { + // state transition 2 + setState(FW_AUTOTAKEOFF_STATE_ABORT); + } else if (downPos < pathDesired->End.Down) { + // state transition 1 + setState(FW_AUTOTAKEOFF_STATE_HOLD); + } + + setAttitude(unsafe); +} + +// run hold loiters like in position hold +// no state transitions (FlyController does exception handling) +void FixedWingAutoTakeoffController::run_hold(void) +{ + // parent controller will do perfect position hold in autotakeoff mode + FixedWingFlyController::UpdateAutoPilot(); +} + +// run abort descends with wings level, engine off (like land) +// no state transitions +void FixedWingAutoTakeoffController::run_abort(void) +{ + setAttitude(true); +} diff --git a/flight/modules/PathFollower/fixedwingflycontroller.cpp b/flight/modules/PathFollower/fixedwingflycontroller.cpp index ed47d0069..d498d41eb 100644 --- a/flight/modules/PathFollower/fixedwingflycontroller.cpp +++ b/flight/modules/PathFollower/fixedwingflycontroller.cpp @@ -26,23 +26,13 @@ extern "C" { #include -#include - -#include #include -#include #include #include #include -#include "plans.h" -#include - -#include -#include #include #include #include -#include #include #include #include @@ -50,14 +40,7 @@ extern "C" { #include #include #include -#include -#include -#include #include -#include -#include -#include -#include } // C++ includes diff --git a/flight/modules/PathFollower/fixedwinglandcontroller.cpp b/flight/modules/PathFollower/fixedwinglandcontroller.cpp new file mode 100644 index 000000000..52727eceb --- /dev/null +++ b/flight/modules/PathFollower/fixedwinglandcontroller.cpp @@ -0,0 +1,143 @@ +/* + ****************************************************************************** + * + * @file FixedWingLandController.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @brief Fixed wing fly controller implementation + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +extern "C" { +#include + +#include +#include +#include +#include +#include +} + +// C++ includes +#include "fixedwinglandcontroller.h" + +// Private constants + +// pointer to a singleton instance +FixedWingLandController *FixedWingLandController::p_inst = 0; + +FixedWingLandController::FixedWingLandController() + : fixedWingSettings(NULL), mActive(false), mMode(0) +{} + +// Called when mode first engaged +void FixedWingLandController::Activate(void) +{ + if (!mActive) { + mActive = true; + SettingsUpdated(); + resetGlobals(); + mMode = pathDesired->Mode; + } +} + +uint8_t FixedWingLandController::IsActive(void) +{ + return mActive; +} + +uint8_t FixedWingLandController::Mode(void) +{ + return mMode; +} + +// Objective updated in pathdesired +void FixedWingLandController::ObjectiveUpdated(void) +{} + +void FixedWingLandController::Deactivate(void) +{ + if (mActive) { + mActive = false; + resetGlobals(); + } +} + + +void FixedWingLandController::SettingsUpdated(void) +{} + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t FixedWingLandController::Initialize(FixedWingPathFollowerSettingsData *ptr_fixedWingSettings) +{ + PIOS_Assert(ptr_fixedWingSettings); + + fixedWingSettings = ptr_fixedWingSettings; + + resetGlobals(); + + return 0; +} + +/** + * reset integrals + */ +void FixedWingLandController::resetGlobals() +{ + pathStatus->path_time = 0.0f; +} + +/** + * fixed wing autopilot + * use fixed attitude heading towards destination waypoint + */ +void FixedWingLandController::UpdateAutoPilot() +{ + StabilizationDesiredData stabDesired; + + stabDesired.Roll = 0.0f; + stabDesired.Pitch = fixedWingSettings->LandingPitch; + stabDesired.Thrust = 0.0f; + stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + stabDesired.StabilizationMode.Thrust = STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL; + + // find out vector direction of *runway* (if any) + // and align, otherwise just stay straight ahead + if (fabsf(pathDesired->Start.North - pathDesired->End.North) < 1e-3f && + fabsf(pathDesired->Start.East - pathDesired->End.East) < 1e-3f) { + stabDesired.Yaw = 0.0f; + stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; + } else { + stabDesired.Yaw = RAD2DEG(atan2f(pathDesired->End.East - pathDesired->Start.East, pathDesired->End.North - pathDesired->Start.North)); + if (stabDesired.Yaw < -180.0f) { + stabDesired.Yaw += 360.0f; + } + if (stabDesired.Yaw > 180.0f) { + stabDesired.Yaw -= 360.0f; + } + stabDesired.StabilizationMode.Yaw = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; + } + StabilizationDesiredSet(&stabDesired); + AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_OK); + + PathStatusSet(pathStatus); +} diff --git a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h new file mode 100644 index 000000000..8b092aa9e --- /dev/null +++ b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h @@ -0,0 +1,87 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup FixedWing CONTROL interface class + * @brief CONTROL interface class for pathfollower fixed wing fly controller + * @{ + * + * @file FixedWingCONTROL.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @brief Executes CONTROL for fixed wing fly objectives + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef FIXEDWINGAUTOTAKEOFFCONTROLLER_H +#define FIXEDWINGAUTOTAKEOFFCONTROLLER_H +#include "fixedwingflycontroller.h" + +// AutoTakeoff state machine +typedef enum { + FW_AUTOTAKEOFF_STATE_INACTIVE = 0, + FW_AUTOTAKEOFF_STATE_LAUNCH, + FW_AUTOTAKEOFF_STATE_CLIMB, + FW_AUTOTAKEOFF_STATE_HOLD, + FW_AUTOTAKEOFF_STATE_ABORT, + FW_AUTOTAKEOFF_STATE_SIZE +} FixedWingAutoTakeoffControllerState_T; + +class FixedWingAutoTakeoffController : public FixedWingFlyController { +public: + void Activate(void); + void UpdateAutoPilot(void); + +private: + // variables + FixedWingAutoTakeoffControllerState_T state; + float initYaw; + float maxVelocity; + + // functions + void setState(FixedWingAutoTakeoffControllerState_T setstate); + void setAttitude(bool unsafe); + float getAirspeed(void); + bool isUnsafe(void); + void run_inactive(void); + void run_launch(void); + void run_climb(void); + void run_hold(void); + void run_abort(void); + void init_inactive(void); + void init_launch(void); + void init_climb(void); + void init_hold(void); + void init_abort(void); + void(FixedWingAutoTakeoffController::*const runFunctionTable[FW_AUTOTAKEOFF_STATE_SIZE]) (void) = { + &FixedWingAutoTakeoffController::run_inactive, + &FixedWingAutoTakeoffController::run_launch, + &FixedWingAutoTakeoffController::run_climb, + &FixedWingAutoTakeoffController::run_hold, + &FixedWingAutoTakeoffController::run_abort + }; + void(FixedWingAutoTakeoffController::*const initFunctionTable[FW_AUTOTAKEOFF_STATE_SIZE]) (void) = { + &FixedWingAutoTakeoffController::init_inactive, + &FixedWingAutoTakeoffController::init_launch, + &FixedWingAutoTakeoffController::init_climb, + &FixedWingAutoTakeoffController::init_hold, + &FixedWingAutoTakeoffController::init_abort + }; +}; + +#endif // FIXEDWINGAUTOTAKEOFFCONTROLLER_H diff --git a/flight/modules/PathFollower/inc/fixedwingflycontroller.h b/flight/modules/PathFollower/inc/fixedwingflycontroller.h index 19dcf4003..45cfcf743 100644 --- a/flight/modules/PathFollower/inc/fixedwingflycontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingflycontroller.h @@ -57,6 +57,13 @@ public: uint8_t Mode(void); void AirspeedStateUpdatedCb(__attribute__((unused)) UAVObjEvent * ev); +protected: + FixedWingPathFollowerSettingsData *fixedWingSettings; + + uint8_t mActive; + uint8_t mMode; + // correct speed by measured airspeed + float indicatedAirspeedStateBias; private: void resetGlobals(); uint8_t updateAutoPilotFixedWing(); @@ -64,17 +71,11 @@ private: uint8_t updateFixedDesiredAttitude(); bool correctCourse(float *C, float *V, float *F, float s); - FixedWingPathFollowerSettingsData *fixedWingSettings; - uint8_t mActive; - uint8_t mMode; - struct pid PIDposH[2]; struct pid PIDposV; struct pid PIDcourse; struct pid PIDspeed; struct pid PIDpower; - // correct speed by measured airspeed - float indicatedAirspeedStateBias; }; #endif // FIXEDWINGFLYCONTROLLER_H diff --git a/flight/modules/PathFollower/inc/fixedwinglandcontroller.h b/flight/modules/PathFollower/inc/fixedwinglandcontroller.h new file mode 100644 index 000000000..17a4e9b44 --- /dev/null +++ b/flight/modules/PathFollower/inc/fixedwinglandcontroller.h @@ -0,0 +1,66 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup FixedWing CONTROL interface class + * @brief CONTROL interface class for pathfollower fixed wing fly controller + * @{ + * + * @file FixedWingCONTROL.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @brief Executes CONTROL for fixed wing fly objectives + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef FIXEDWINGLANDCONTROLLER_H +#define FIXEDWINGLANDCONTROLLER_H +#include "pathfollowercontrol.h" + +class FixedWingLandController : public PathFollowerControl { +private: + static FixedWingLandController *p_inst; + FixedWingLandController(); + + +public: + static FixedWingLandController *instance() + { + if (!p_inst) { + p_inst = new FixedWingLandController(); + } + return p_inst; + } + + int32_t Initialize(FixedWingPathFollowerSettingsData *fixedWingSettings); + void Activate(void); + void Deactivate(void); + void SettingsUpdated(void); + void UpdateAutoPilot(void); + void ObjectiveUpdated(void); + uint8_t IsActive(void); + uint8_t Mode(void); + +private: + void resetGlobals(); + FixedWingPathFollowerSettingsData *fixedWingSettings; + uint8_t mActive; + uint8_t mMode; +}; + +#endif // FIXEDWINGLANDCONTROLLER_H diff --git a/flight/modules/PathFollower/pathfollower.cpp b/flight/modules/PathFollower/pathfollower.cpp index f96328965..e73ad8c24 100644 --- a/flight/modules/PathFollower/pathfollower.cpp +++ b/flight/modules/PathFollower/pathfollower.cpp @@ -93,6 +93,8 @@ extern "C" { #include "vtolbrakecontroller.h" #include "vtolflycontroller.h" #include "fixedwingflycontroller.h" +#include "fixedwingautotakeoffcontroller.h" +#include "fixedwinglandcontroller.h" #include "grounddrivecontroller.h" // Private constants @@ -220,6 +222,8 @@ void pathFollowerInitializeControllersForFrameType() case FRAME_TYPE_FIXED_WING: if (!fixedwing_initialised) { FixedWingFlyController::instance()->Initialize(&fixedWingPathFollowerSettings); + FixedWingAutoTakeoffController::instance()->Initialize(&fixedWingPathFollowerSettings); + FixedWingLandController::instance()->Initialize(&fixedWingPathFollowerSettings); fixedwing_initialised = 1; } break; @@ -289,6 +293,14 @@ static void pathFollowerSetActiveController(void) activeController = FixedWingFlyController::instance(); activeController->Activate(); break; + case PATHDESIRED_MODE_LAND: // land with optional velocity roam option + activeController = FixedWingLandController::instance(); + activeController->Activate(); + break; + case PATHDESIRED_MODE_AUTOTAKEOFF: + activeController = FixedWingAutoTakeoffController::instance(); + activeController->Activate(); + break; default: activeController = 0; AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_UNINITIALISED); @@ -451,6 +463,7 @@ static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) static void airspeedStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { FixedWingFlyController::instance()->AirspeedStateUpdatedCb(ev); + FixedWingAutoTakeoffController::instance()->AirspeedStateUpdatedCb(ev); } From 9a6cf9d21b96691b6a41230aa0db678fbfb1c239 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 10:02:53 +0200 Subject: [PATCH 03/58] OP-1900 OP-1054 added emergency thrust cutoff feature to main fixed wing autopilot on loss of control --- .../fixedwingautotakeoffcontroller.cpp | 8 ++-- .../PathFollower/fixedwingflycontroller.cpp | 48 ++++++++++++++++--- .../fixedwingpathfollowersettings.xml | 14 ++++-- .../fixedwingpathfollowerstatus.xml | 2 +- 4 files changed, 55 insertions(+), 17 deletions(-) diff --git a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp index 437920d8f..bd289992d 100644 --- a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp @@ -142,10 +142,10 @@ bool FixedWingAutoTakeoffController::isUnsafe(void) AttitudeStateData attitude; AttitudeStateGet(&attitude); // too much bank angle - if (fabsf(attitude.Roll) > fixedWingSettings->TakeOffLimits.RollDeg) { + if (fabsf(attitude.Roll) > fixedWingSettings->SafetyCutoffLimits.RollDeg) { abort = true; } - if (fabsf(attitude.Pitch - fixedWingSettings->TakeOffPitch) > fixedWingSettings->TakeOffLimits.PitchDeg) { + if (fabsf(attitude.Pitch - fixedWingSettings->TakeOffPitch) > fixedWingSettings->SafetyCutoffLimits.PitchDeg) { abort = true; } float deltayaw = attitude.Yaw - initYaw; @@ -155,7 +155,7 @@ bool FixedWingAutoTakeoffController::isUnsafe(void) if (deltayaw < -180.0f) { deltayaw += 360.0f; } - if (fabsf(deltayaw) > fixedWingSettings->TakeOffLimits.YawDeg) { + if (fabsf(deltayaw) > fixedWingSettings->SafetyCutoffLimits.YawDeg) { abort = true; } return abort; @@ -206,7 +206,7 @@ void FixedWingAutoTakeoffController::run_inactive(void) {} void FixedWingAutoTakeoffController::run_launch(void) { // state transition - if (maxVelocity > fixedWingSettings->TakeOffLimits.MaxDecelerationDeltaMPS) { + if (maxVelocity > fixedWingSettings->SafetyCutoffLimits.MaxDecelerationDeltaMPS) { setState(FW_AUTOTAKEOFF_STATE_CLIMB); } diff --git a/flight/modules/PathFollower/fixedwingflycontroller.cpp b/flight/modules/PathFollower/fixedwingflycontroller.cpp index d498d41eb..3721fb1e1 100644 --- a/flight/modules/PathFollower/fixedwingflycontroller.cpp +++ b/flight/modules/PathFollower/fixedwingflycontroller.cpp @@ -228,6 +228,7 @@ void FixedWingFlyController::updatePathVelocity(float kFF, bool limited) uint8_t FixedWingFlyController::updateFixedDesiredAttitude() { uint8_t result = 1; + bool cutThrust = false; const float dT = fixedWingSettings->UpdatePeriod / 1000.0f; @@ -333,6 +334,7 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() if (indicatedAirspeedState > fixedWingSettings->HorizontalVelMax * fixedWingSettings->Safetymargins.Highspeed) { fixedWingPathFollowerStatus.Errors.Highspeed = 1; result = 0; + cutThrust = true; } if (indicatedAirspeedState < fixedWingSettings->HorizontalVelMin * fixedWingSettings->Safetymargins.Lowspeed) { fixedWingPathFollowerStatus.Errors.Lowspeed = 1; @@ -342,6 +344,10 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() fixedWingPathFollowerStatus.Errors.Stallspeed = 1; result = 0; } + if (indicatedAirspeedState < fixedWingSettings->HorizontalVelMin * fixedWingSettings->Safetymargins.Lowspeed - fixedWingSettings->SafetyCutoffLimits.MaxDecelerationDeltaMPS) { + cutThrust = true; + result = 0; + } /** * Compute desired thrust command @@ -373,20 +379,26 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() if (fixedWingSettings->ThrustLimit.Neutral + powerCommand >= fixedWingSettings->ThrustLimit.Max && // thrust at maximum velocityState.Down > 0.0f && // we ARE going down descentspeedDesired < 0.0f && // we WANT to go up - airspeedError > 0.0f && // we are too slow already - fixedWingSettings->Safetymargins.Lowpower > 0.5f) { // alarm switched on + airspeedError > 0.0f) { // we are too slow already fixedWingPathFollowerStatus.Errors.Lowpower = 1; - result = 0; + + if (fixedWingSettings->Safetymargins.Lowpower > 0.5f) { // alarm switched on + result = 0; + } } // Error condition: plane keeps climbing despite minimum thrust (opposite of above) fixedWingPathFollowerStatus.Errors.Highpower = 0; if (fixedWingSettings->ThrustLimit.Neutral + powerCommand <= fixedWingSettings->ThrustLimit.Min && // thrust at minimum velocityState.Down < 0.0f && // we ARE going up descentspeedDesired > 0.0f && // we WANT to go down - airspeedError < 0.0f && // we are too fast already - fixedWingSettings->Safetymargins.Highpower > 0.5f) { // alarm switched on + airspeedError < 0.0f) { // we are too fast already + // this alarm is often switched off because of false positives, however we still want to cut throttle if it happens + cutThrust = true; fixedWingPathFollowerStatus.Errors.Highpower = 1; - result = 0; + + if (fixedWingSettings->Safetymargins.Highpower > 0.5f) { // alarm switched on + result = 0; + } } /** @@ -418,7 +430,17 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() fixedWingSettings->Safetymargins.Pitchcontrol > 0.5f) { // alarm switched on fixedWingPathFollowerStatus.Errors.Pitchcontrol = 1; result = 0; + cutThrust = true; } + // Error condition: pitch way out of wack + if (fixedWingSettings->Safetymargins.Pitchcontrol > 0.5f && + (attitudeState.Pitch < fixedWingSettings->PitchLimit.Min - fixedWingSettings->SafetyCutoffLimits.PitchDeg || + attitudeState.Pitch > fixedWingSettings->PitchLimit.Max + fixedWingSettings->SafetyCutoffLimits.PitchDeg)) { + fixedWingPathFollowerStatus.Errors.Pitchcontrol = 1; + result = 0; + cutThrust = true; + } + /** * Compute desired roll command @@ -456,7 +478,15 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() fixedWingSettings->RollLimit.Min, fixedWingSettings->RollLimit.Max); - // TODO: find a check to determine loss of directional control. Likely needs some check of derivative + // Error condition: roll way out of wack + fixedWingPathFollowerStatus.Errors.Rollcontrol = 0; + if (fixedWingSettings->Safetymargins.Rollcontrol > 0.5f && + (attitudeState.Roll < fixedWingSettings->RollLimit.Min - fixedWingSettings->SafetyCutoffLimits.RollDeg || + attitudeState.Roll > fixedWingSettings->RollLimit.Max + fixedWingSettings->SafetyCutoffLimits.RollDeg)) { + fixedWingPathFollowerStatus.Errors.Rollcontrol = 1; + result = 0; + cutThrust = true; + } /** @@ -465,6 +495,10 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() // TODO implement raw control mode for yaw and base on Accels.Y stabDesired.Yaw = 0.0f; + // safety cutoff condition + if (cutThrust) { + stabDesired.Thrust = 0.0f; + } stabDesired.StabilizationMode.Roll = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; stabDesired.StabilizationMode.Pitch = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml index 230eebbc8..58f2b0d19 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -45,17 +45,21 @@ + elementnames="Wind, Stallspeed, Lowspeed, Highspeed, Overspeed, Lowpower, Highpower, Rollcontrol, Pitchcontrol" + defaultvalue="1, 1.0, 0.5, 1.5, 1.0, 1, 1, 1, 1" /> + + - - diff --git a/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml b/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml index fe31830db..2b2482de9 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml @@ -4,7 +4,7 @@ - + From eb9a13597795bf447c807e1a5462b731c077b871 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 10:45:56 +0200 Subject: [PATCH 04/58] OP-1900 manual induced autotakeoff sequencing safer for multis and fixed wing --- flight/libraries/plans.c | 39 +++++++++++++++++++++++++++++---------- 1 file changed, 29 insertions(+), 10 deletions(-) diff --git a/flight/libraries/plans.c b/flight/libraries/plans.c index 1ed4d6e11..6b242105d 100644 --- a/flight/libraries/plans.c +++ b/flight/libraries/plans.c @@ -43,6 +43,7 @@ #include #include #include +#include #include #define UPDATE_EXPECTED 0.02f @@ -219,6 +220,14 @@ static void plan_setup_AutoTakeoff_helper(PathDesiredData *pathDesired) #define AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT 0.2f void plan_setup_AutoTakeoff() { + FrameType_t frame = GetCurrentFrameType(); + VtolPathFollowerSettingsTreatCustomCraftAsOptions TreatCustomCraftAs; + + VtolPathFollowerSettingsTreatCustomCraftAsGet(&TreatCustomCraftAs); + if (frame == FRAME_TYPE_CUSTOM && TreatCustomCraftAs == VTOLPATHFOLLOWERSETTINGS_TREATCUSTOMCRAFTAS_FIXEDWING) { + frame = FRAME_TYPE_FIXED_WING; + } + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED; // We only allow takeoff if the state transition of disarmed to armed occurs // whilst in the autotake flight mode @@ -227,18 +236,28 @@ void plan_setup_AutoTakeoff() StabilizationDesiredData stabiDesired; StabilizationDesiredGet(&stabiDesired); - // Are we inflight? - if (flightStatus.Armed && stabiDesired.Thrust > AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT) { - // ok assume already in flight and just enter position hold - // if we are not actually inflight this will just be a violent autotakeoff - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD; - plan_setup_positionHold(); + if (frame != FRAME_TYPE_FIXED_WING) { + // Are we inflight? + if (flightStatus.Armed && stabiDesired.Thrust > AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT) { + // ok assume already in flight and just enter position hold + // if we are not actually inflight this will just be a violent autotakeoff + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD; + plan_setup_positionHold(); + } else { + if (flightStatus.Armed) { + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST; + // Note that if this mode was invoked unintentionally whilst in flight, effectively + // all inputs get ignored and the vtol continues to fly to its previous + // stabi command. + } + PathDesiredData pathDesired; + plan_setup_AutoTakeoff_helper(&pathDesired); + PathDesiredSet(&pathDesired); + } } else { + // fixed wings do not require arming - or sequencing, as the takeoffcontroller has its own independent state machine if (flightStatus.Armed) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST; - // Note that if this mode was invoked unintentionally whilst in flight, effectively - // all inputs get ignored and the vtol continues to fly to its previous - // stabi command. + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE; } PathDesiredData pathDesired; plan_setup_AutoTakeoff_helper(&pathDesired); From d7f049052271d932a40757df2b55ff6392260592 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 12:07:27 +0200 Subject: [PATCH 05/58] OP-1900 fixed header file name references --- .../modules/PathFollower/inc/fixedwingautotakeoffcontroller.h | 2 +- flight/modules/PathFollower/inc/fixedwingflycontroller.h | 2 +- flight/modules/PathFollower/inc/fixedwinglandcontroller.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h index 8b092aa9e..3649addad 100644 --- a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h @@ -6,7 +6,7 @@ * @brief CONTROL interface class for pathfollower fixed wing fly controller * @{ * - * @file FixedWingCONTROL.h + * @file fxedwingautotakeoffcontroller.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for fixed wing fly objectives * diff --git a/flight/modules/PathFollower/inc/fixedwingflycontroller.h b/flight/modules/PathFollower/inc/fixedwingflycontroller.h index 45cfcf743..8159df8f1 100644 --- a/flight/modules/PathFollower/inc/fixedwingflycontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingflycontroller.h @@ -6,7 +6,7 @@ * @brief CONTROL interface class for pathfollower fixed wing fly controller * @{ * - * @file FixedWingCONTROL.h + * @file fixedwingflycontroller.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for fixed wing fly objectives * diff --git a/flight/modules/PathFollower/inc/fixedwinglandcontroller.h b/flight/modules/PathFollower/inc/fixedwinglandcontroller.h index 17a4e9b44..9643dea8c 100644 --- a/flight/modules/PathFollower/inc/fixedwinglandcontroller.h +++ b/flight/modules/PathFollower/inc/fixedwinglandcontroller.h @@ -6,7 +6,7 @@ * @brief CONTROL interface class for pathfollower fixed wing fly controller * @{ * - * @file FixedWingCONTROL.h + * @file fixedwinglandcontroller.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for fixed wing fly objectives * From fe01c6c69edcf1110f310673897fa470610fdbb4 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 12:47:29 +0200 Subject: [PATCH 06/58] give me an I! --- .../modules/PathFollower/inc/fixedwingautotakeoffcontroller.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h index 3649addad..c45202b37 100644 --- a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h @@ -6,7 +6,7 @@ * @brief CONTROL interface class for pathfollower fixed wing fly controller * @{ * - * @file fxedwingautotakeoffcontroller.h + * @file fixedwingautotakeoffcontroller.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for fixed wing fly objectives * From 359c2ec560dc323daa3ff90c07452a49a28b2604 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 15:19:09 +0200 Subject: [PATCH 07/58] disable stackoverflow checks on simposix - it doesnt work and the systemalarm prevents arming --- flight/modules/System/systemmod.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/modules/System/systemmod.c b/flight/modules/System/systemmod.c index 8c94ec1b1..9c6324e03 100644 --- a/flight/modules/System/systemmod.c +++ b/flight/modules/System/systemmod.c @@ -441,9 +441,11 @@ static void callbackSchedulerForEachCallback(int16_t callback_id, const struct p return; } // delayed callback scheduler reports callback stack overflows as remaininng: -1 +#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) if (callback_info->stack_remaining < 0 && stackOverflow == STACKOVERFLOW_NONE) { stackOverflow = STACKOVERFLOW_WARNING; } +#endif // By convention, there is a direct mapping between (not negative) callback scheduler callback_id's and members // of the CallbackInfoXXXXElem enums PIOS_DEBUG_Assert(callback_id < CALLBACKINFO_RUNNING_NUMELEM); @@ -654,6 +656,7 @@ void vApplicationIdleHook(void) void vApplicationStackOverflowHook(__attribute__((unused)) xTaskHandle *pxTask, __attribute__((unused)) signed portCHAR *pcTaskName) { +#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) stackOverflow = STACKOVERFLOW_CRITICAL; #if DEBUG_STACK_OVERFLOW static volatile bool wait_here = true; @@ -662,6 +665,7 @@ void vApplicationStackOverflowHook(__attribute__((unused)) xTaskHandle *pxTask, } wait_here = true; #endif +#endif } /** From ffcd058478ac806b638d1230a2068b974f5338df Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 15:41:59 +0200 Subject: [PATCH 08/58] fix flightgear hitl bridge sign issue on velocity down vector --- ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp b/ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp index eb53b75fb..aa0bd4b88 100644 --- a/ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp @@ -269,7 +269,7 @@ void FGSimulator::processUpdate(const QByteArray & inp) // Get pressure (kpa) float pressure = fields[20].toFloat() * INHG2KPA; // Get VelocityState Down (m/s) - float velocityStateDown = -fields[21].toFloat() * FPS2CMPS * 1e-2f; + float velocityStateDown = fields[21].toFloat() * FPS2CMPS * 1e-2f; // Get VelocityState East (m/s) float velocityStateEast = fields[22].toFloat() * FPS2CMPS * 1e-2f; // Get VelocityState Down (m/s) From 4b7edee534d771d6e7f51cde2a54d97401623255 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 17:11:19 +0200 Subject: [PATCH 09/58] OP-1900 Fixed Constructor calling chain --- .../PathFollower/fixedwingautotakeoffcontroller.cpp | 4 ++++ .../PathFollower/inc/fixedwingautotakeoffcontroller.h | 10 ++++++++++ .../modules/PathFollower/inc/fixedwingflycontroller.h | 2 +- 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp index bd289992d..d50d3318e 100644 --- a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp @@ -43,6 +43,10 @@ extern "C" { // Private constants +// pointer to a singleton instance +FixedWingAutoTakeoffController *FixedWingAutoTakeoffController::p_inst = 0; + + // Called when mode first engaged void FixedWingAutoTakeoffController::Activate(void) { diff --git a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h index c45202b37..6fc06fafe 100644 --- a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h @@ -43,7 +43,17 @@ typedef enum { } FixedWingAutoTakeoffControllerState_T; class FixedWingAutoTakeoffController : public FixedWingFlyController { +protected: + static FixedWingAutoTakeoffController *p_inst; + public: + static FixedWingFlyController *instance() + { + if (!p_inst) { + p_inst = new FixedWingAutoTakeoffController(); + } + return p_inst; + } void Activate(void); void UpdateAutoPilot(void); diff --git a/flight/modules/PathFollower/inc/fixedwingflycontroller.h b/flight/modules/PathFollower/inc/fixedwingflycontroller.h index 8159df8f1..c79b0644c 100644 --- a/flight/modules/PathFollower/inc/fixedwingflycontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingflycontroller.h @@ -33,7 +33,7 @@ #include "pathfollowercontrol.h" class FixedWingFlyController : public PathFollowerControl { -private: +protected: static FixedWingFlyController *p_inst; FixedWingFlyController(); From ccfe39633e81f41137acfef9e88ded615761f14c Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sat, 23 May 2015 22:17:32 +0200 Subject: [PATCH 10/58] OP-1900 Put Sequencing state machine for vixed wing autotakeoff out of plan.c and into vtolautotakeoffcontroller, removed all special casing for autotakeoff and land from outside of pathfollower itself and code in plans.c - especially cleaned up pathplanner.c and made mode agnostic (which it should be) - added optional rewinding for pathplans --- flight/libraries/plans.c | 173 ++-------------- .../ManualControl/pathfollowerhandler.c | 3 - .../inc/vtolautotakeoffcontroller.h | 2 + .../PathFollower/inc/vtolautotakeofffsm.h | 2 +- .../PathFollower/inc/vtollandcontroller.h | 1 + .../vtolautotakeoffcontroller.cpp | 151 +++++++++++++- .../PathFollower/vtollandcontroller.cpp | 26 ++- flight/modules/PathPlanner/pathplanner.c | 191 ++++-------------- .../flightmodesettings.xml | 1 + 9 files changed, 228 insertions(+), 322 deletions(-) diff --git a/flight/libraries/plans.c b/flight/libraries/plans.c index 6b242105d..a5fed1dd3 100644 --- a/flight/libraries/plans.c +++ b/flight/libraries/plans.c @@ -169,172 +169,33 @@ void plan_setup_returnToBase() PathDesiredSet(&pathDesired); } - -// Vtol AutoTakeoff invocation from flight mode requires the following sequence: -// 1. Arming must be done whilst in the AutoTakeOff flight mode -// 2. If the AutoTakeoff flight mode is selected and already armed, requires disarming first -// 3. Wait for armed state -// 4. Once the user increases the throttle position to above 50%, then and only then initiate auto-takeoff. -// 5. Whilst the throttle is < 50% before takeoff, all stick inputs are being ignored. -// 6. If during the autotakeoff sequence, at any stage, if the throttle stick position reduces to less than 10%, landing is initiated. - -static StatusVtolAutoTakeoffControlStateOptions autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED; - -#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN 2.0f -#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX 50.0f -static void plan_setup_AutoTakeoff_helper(PathDesiredData *pathDesired) +void plan_setup_AutoTakeoff() { + PathDesiredData pathDesired; PositionStateData positionState; PositionStateGet(&positionState); - float velocity_down; float autotakeoff_height; - FlightModeSettingsAutoTakeOffVelocityGet(&velocity_down); FlightModeSettingsAutoTakeOffHeightGet(&autotakeoff_height); - autotakeoff_height = fabsf(autotakeoff_height); - if (autotakeoff_height < AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN) { - autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN; - } else if (autotakeoff_height > AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX) { - autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX; - } + autotakeoff_height = fabsf(autotakeoff_height); + pathDesired.Start.North = positionState.North; + pathDesired.Start.East = positionState.East; + pathDesired.Start.Down = positionState.Down; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH] = 0.0f; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST] = 0.0f; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN] = 0.0f; + pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] = 0.0f; - pathDesired->Start.North = positionState.North; - pathDesired->Start.East = positionState.East; - pathDesired->Start.Down = positionState.Down; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH] = 0.0f; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST] = 0.0f; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN] = -velocity_down; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] = (float)autotakeoffState; + pathDesired.End.North = positionState.North; + pathDesired.End.East = positionState.East; + pathDesired.End.Down = positionState.Down - autotakeoff_height; - pathDesired->End.North = positionState.North; - pathDesired->End.East = positionState.East; - pathDesired->End.Down = positionState.Down - autotakeoff_height; - - pathDesired->StartingVelocity = 0.0f; - pathDesired->EndingVelocity = 0.0f; - pathDesired->Mode = PATHDESIRED_MODE_AUTOTAKEOFF; -} - -#define AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT 0.2f -void plan_setup_AutoTakeoff() -{ - FrameType_t frame = GetCurrentFrameType(); - VtolPathFollowerSettingsTreatCustomCraftAsOptions TreatCustomCraftAs; - - VtolPathFollowerSettingsTreatCustomCraftAsGet(&TreatCustomCraftAs); - if (frame == FRAME_TYPE_CUSTOM && TreatCustomCraftAs == VTOLPATHFOLLOWERSETTINGS_TREATCUSTOMCRAFTAS_FIXEDWING) { - frame = FRAME_TYPE_FIXED_WING; - } - - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED; - // We only allow takeoff if the state transition of disarmed to armed occurs - // whilst in the autotake flight mode - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); - StabilizationDesiredData stabiDesired; - StabilizationDesiredGet(&stabiDesired); - - if (frame != FRAME_TYPE_FIXED_WING) { - // Are we inflight? - if (flightStatus.Armed && stabiDesired.Thrust > AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT) { - // ok assume already in flight and just enter position hold - // if we are not actually inflight this will just be a violent autotakeoff - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD; - plan_setup_positionHold(); - } else { - if (flightStatus.Armed) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST; - // Note that if this mode was invoked unintentionally whilst in flight, effectively - // all inputs get ignored and the vtol continues to fly to its previous - // stabi command. - } - PathDesiredData pathDesired; - plan_setup_AutoTakeoff_helper(&pathDesired); - PathDesiredSet(&pathDesired); - } - } else { - // fixed wings do not require arming - or sequencing, as the takeoffcontroller has its own independent state machine - if (flightStatus.Armed) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE; - } - PathDesiredData pathDesired; - plan_setup_AutoTakeoff_helper(&pathDesired); - PathDesiredSet(&pathDesired); - } -} - -#define AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START 0.3f -#define AUTOTAKEOFF_THROTTLE_ABORT_LIMIT 0.1f -void plan_run_AutoTakeoff() -{ - StatusVtolAutoTakeoffControlStateOptions priorState = autotakeoffState; - - switch (autotakeoffState) { - case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST: - { - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); - if (!flightStatus.Armed) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE; - } - } - break; - case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED: - { - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); - if (flightStatus.Armed) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE; - } - } - break; - case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE: - { - ManualControlCommandData cmd; - ManualControlCommandGet(&cmd); - - if (cmd.Throttle > AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE; - } - } - break; - case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE: - { - ManualControlCommandData cmd; - ManualControlCommandGet(&cmd); - - if (cmd.Throttle < AUTOTAKEOFF_THROTTLE_ABORT_LIMIT) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT; - plan_setup_land(); - } - } - break; - - case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT: - { - FlightStatusData flightStatus; - FlightStatusGet(&flightStatus); - if (!flightStatus.Armed) { - autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED; - } - } - break; - case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD: - // nothing to do. land has been requested. stay here for forever until mode change. - default: - break; - } - - if (autotakeoffState != STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT && - autotakeoffState != STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD) { - if (priorState != autotakeoffState) { - PathDesiredData pathDesired; - plan_setup_AutoTakeoff_helper(&pathDesired); - PathDesiredSet(&pathDesired); - } - } + pathDesired.StartingVelocity = 0.0f; + pathDesired.EndingVelocity = 0.0f; + pathDesired.Mode = PATHDESIRED_MODE_AUTOTAKEOFF; + PathDesiredSet(&pathDesired); } static void plan_setup_land_helper(PathDesiredData *pathDesired) diff --git a/flight/modules/ManualControl/pathfollowerhandler.c b/flight/modules/ManualControl/pathfollowerhandler.c index 202c833b8..0d5c8078d 100644 --- a/flight/modules/ManualControl/pathfollowerhandler.c +++ b/flight/modules/ManualControl/pathfollowerhandler.c @@ -140,9 +140,6 @@ void pathFollowerHandler(bool newinit) plan_run_VelocityRoam(); } break; - case FLIGHTSTATUS_FLIGHTMODE_AUTOTAKEOFF: - plan_run_AutoTakeoff(); - break; case FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE: plan_run_AutoCruise(); break; diff --git a/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h b/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h index 4b52bfa9c..b7d103618 100644 --- a/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h +++ b/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h @@ -70,6 +70,8 @@ private: PIDControlDown controlDown; PIDControlNE controlNE; uint8_t mActive; + uint8_t mOverride; + StatusVtolAutoTakeoffControlStateOptions autotakeoffState; }; #endif // VTOLAUTOTAKEOFFCONTROLLER_H diff --git a/flight/modules/PathFollower/inc/vtolautotakeofffsm.h b/flight/modules/PathFollower/inc/vtolautotakeofffsm.h index 6c912baec..f683ee33c 100644 --- a/flight/modules/PathFollower/inc/vtolautotakeofffsm.h +++ b/flight/modules/PathFollower/inc/vtolautotakeofffsm.h @@ -47,7 +47,7 @@ typedef enum { AUTOTAKEOFF_STATE_THRUSTDOWN, // Thrust down sequence AUTOTAKEOFF_STATE_THRUSTOFF, // Thrust is now off AUTOTAKEOFF_STATE_DISARMED, // Disarmed - AUTOTAKEOFF_STATE_ABORT, // Abort on error triggerig fallback to hold + AUTOTAKEOFF_STATE_ABORT, // Abort on error triggerig fallback to land AUTOTAKEOFF_STATE_SIZE } PathFollowerFSM_AutoTakeoffState_T; diff --git a/flight/modules/PathFollower/inc/vtollandcontroller.h b/flight/modules/PathFollower/inc/vtollandcontroller.h index c770df0b3..0c3039629 100644 --- a/flight/modules/PathFollower/inc/vtollandcontroller.h +++ b/flight/modules/PathFollower/inc/vtollandcontroller.h @@ -71,6 +71,7 @@ private: PIDControlDown controlDown; PIDControlNE controlNE; uint8_t mActive; + uint8_t mOverride; }; #endif // VTOLLANDCONTROLLER_H diff --git a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp index afac9e7e5..5087adaff 100644 --- a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp @@ -57,6 +57,7 @@ extern "C" { #include #include #include +#include #include } @@ -67,6 +68,11 @@ extern "C" { #include "pidcontroldown.h" // Private constants +#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN 2.0f +#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX 50.0f +#define AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT 0.2f +#define AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START 0.3f +#define AUTOTAKEOFF_THROTTLE_ABORT_LIMIT 0.1f // pointer to a singleton instance VtolAutoTakeoffController *VtolAutoTakeoffController::p_inst = 0; @@ -79,11 +85,34 @@ VtolAutoTakeoffController::VtolAutoTakeoffController() void VtolAutoTakeoffController::Activate(void) { if (!mActive) { - mActive = true; + mActive = true; + mOverride = true; SettingsUpdated(); fsm->Activate(); controlDown.Activate(); controlNE.Activate(); + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED; + // We only allow takeoff if the state transition of disarmed to armed occurs + // whilst in the autotake flight mode + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + StabilizationDesiredData stabiDesired; + StabilizationDesiredGet(&stabiDesired); + + if (flightStatus.Armed) { + // Are we inflight? + if (stabiDesired.Thrust > AUTOTAKEOFF_INFLIGHT_THROTTLE_CHECK_LIMIT || flightStatus.ControlChain.PathPlanner == FLIGHTSTATUS_CONTROLCHAIN_TRUE) { + // ok assume already in flight and just enter position hold + // if we are not actually inflight this will just be a violent autotakeoff + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD; + } else { + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST; + // Note that if this mode was invoked unintentionally whilst in flight, effectively + // all inputs get ignored and the vtol continues to fly to its previous + // stabi command. + } + } + fsm->setControlState(autotakeoffState); } } @@ -100,14 +129,37 @@ uint8_t VtolAutoTakeoffController::Mode(void) // Objective updated in pathdesired, e.g. same flight mode but new target velocity void VtolAutoTakeoffController::ObjectiveUpdated(void) { - // Set the objective's target velocity + if (mOverride) { + // override pathDesired from PathPLanner with current position, + // as we deliberately don' not care about the location of the waypoints on the map + float velocity_down; + float autotakeoff_height; + PositionStateData positionState; + PositionStateGet(&positionState); + FlightModeSettingsAutoTakeOffVelocityGet(&velocity_down); + FlightModeSettingsAutoTakeOffHeightGet(&autotakeoff_height); + autotakeoff_height = fabsf(autotakeoff_height); + if (autotakeoff_height < AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN) { + autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN; + } else if (autotakeoff_height > AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX) { + autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX; + } + controlDown.UpdateVelocitySetpoint(velocity_down); + controlNE.UpdateVelocitySetpoint(0.0f, 0.0f); + controlNE.UpdatePositionSetpoint(positionState.North, positionState.East); - controlDown.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN]); - controlNE.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH], - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST]); - controlNE.UpdatePositionSetpoint(pathDesired->End.North, pathDesired->End.East); - controlDown.UpdatePositionSetpoint(pathDesired->End.Down); - fsm->setControlState((StatusVtolAutoTakeoffControlStateOptions)pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE]); + + controlDown.UpdatePositionSetpoint(positionState.Down - autotakeoff_height); + mOverride = false; // further updates always come from ManualControl and will control horizontal position + } else { + // Set the objective's target velocity + + controlDown.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN]); + controlNE.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH], + pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST]); + controlNE.UpdatePositionSetpoint(pathDesired->End.North, pathDesired->End.East); + controlDown.UpdatePositionSetpoint(pathDesired->End.Down); + } } void VtolAutoTakeoffController::Deactivate(void) { @@ -224,6 +276,16 @@ int8_t VtolAutoTakeoffController::UpdateStabilizationDesired() controlNE.GetNECommand(&northCommand, &eastCommand); stabDesired.Thrust = controlDown.GetDownCommand(); + switch (autotakeoffState) { + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED: + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE: + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST: + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT: + stabDesired.Thrust = 0.0f; + break; + default: + break; + } float angle_radians = DEG2RAD(attitudeState.Yaw); float cos_angle = cosf(angle_radians); @@ -251,6 +313,79 @@ int8_t VtolAutoTakeoffController::UpdateStabilizationDesired() void VtolAutoTakeoffController::UpdateAutoPilot() { + // state machine updates: + // Vtol AutoTakeoff invocation from flight mode requires the following sequence: + // 1. Arming must be done whilst in the AutoTakeOff flight mode + // 2. If the AutoTakeoff flight mode is selected and already armed, requires disarming first + // 3. Wait for armed state + // 4. Once the user increases the throttle position to above 50%, then and only then initiate auto-takeoff. + // 5. Whilst the throttle is < 50% before takeoff, all stick inputs are being ignored. + // 6. If during the autotakeoff sequence, at any stage, if the throttle stick position reduces to less than 10%, landing is initiated. + + switch (autotakeoffState) { + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_REQUIREUNARMEDFIRST: + { + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + if (!flightStatus.Armed) { + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED; + fsm->setControlState(autotakeoffState); + } + } + break; + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED: + { + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + if (flightStatus.Armed) { + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE; + fsm->setControlState(autotakeoffState); + } + } + break; + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE: + { + ManualControlCommandData cmd; + ManualControlCommandGet(&cmd); + + if (cmd.Throttle > AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START) { + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE; + fsm->setControlState(autotakeoffState); + } + } + break; + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE: + { + ManualControlCommandData cmd; + ManualControlCommandGet(&cmd); + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + + // we do not do a takeoff abort in pathplanner mode + if (flightStatus.ControlChain.PathPlanner != FLIGHTSTATUS_CONTROLCHAIN_TRUE && + cmd.Throttle < AUTOTAKEOFF_THROTTLE_ABORT_LIMIT) { + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT; + fsm->setControlState(autotakeoffState); + } + } + break; + + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT: + { + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + if (!flightStatus.Armed) { + autotakeoffState = STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORARMED; + fsm->setControlState(autotakeoffState); + } + } + break; + case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_POSITIONHOLD: + // nothing to do. land has been requested. stay here for forever until mode change. + default: + break; + } + fsm->Update(); UpdateVelocityDesired(); diff --git a/flight/modules/PathFollower/vtollandcontroller.cpp b/flight/modules/PathFollower/vtollandcontroller.cpp index c2546ed37..07e02e80c 100644 --- a/flight/modules/PathFollower/vtollandcontroller.cpp +++ b/flight/modules/PathFollower/vtollandcontroller.cpp @@ -76,7 +76,8 @@ VtolLandController::VtolLandController() void VtolLandController::Activate(void) { if (!mActive) { - mActive = true; + mActive = true; + mOverride = true; SettingsUpdated(); fsm->Activate(); controlDown.Activate(); @@ -97,11 +98,24 @@ uint8_t VtolLandController::Mode(void) // Objective updated in pathdesired, e.g. same flight mode but new target velocity void VtolLandController::ObjectiveUpdated(void) { - // Set the objective's target velocity - controlDown.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_DOWN]); - controlNE.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_NORTH], - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_EAST]); - controlNE.UpdatePositionSetpoint(pathDesired->End.North, pathDesired->End.East); + if (mOverride) { + // override pathDesired from PathPLanner with current position, + // as we deliberately don' not care about the location of the waypoints on the map + float velocity_down; + PositionStateData positionState; + PositionStateGet(&positionState); + FlightModeSettingsLandingVelocityGet(&velocity_down); + controlDown.UpdateVelocitySetpoint(velocity_down); + controlNE.UpdateVelocitySetpoint(0.0f, 0.0f); + controlNE.UpdatePositionSetpoint(positionState.North, positionState.East); + mOverride = false; // further updates always come from ManualControl and will control horizontal position + } else { + // Set the objective's target velocity + controlDown.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_DOWN]); + controlNE.UpdateVelocitySetpoint(pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_NORTH], + pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_VELOCITY_VELOCITYVECTOR_EAST]); + controlNE.UpdatePositionSetpoint(pathDesired->End.North, pathDesired->End.East); + } } void VtolLandController::Deactivate(void) { diff --git a/flight/modules/PathPlanner/pathplanner.c b/flight/modules/PathPlanner/pathplanner.c index c22c816bc..75bd1336a 100644 --- a/flight/modules/PathPlanner/pathplanner.c +++ b/flight/modules/PathPlanner/pathplanner.c @@ -48,8 +48,6 @@ #include "plans.h" #include #include -#include -#include #include // Private constants @@ -80,9 +78,6 @@ static uint8_t conditionPointingTowardsNext(); static uint8_t conditionPythonScript(); static uint8_t conditionImmediate(); static void SettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev); -static void planner_setup_pathdesired_land(PathDesiredData *pathDesired); -static void planner_setup_pathdesired_takeoff(PathDesiredData *pathDesired); -static void planner_setup_pathdesired(PathDesiredData *pathDesired, bool overwrite_start_position); // Private variables @@ -132,8 +127,6 @@ int32_t PathPlannerInitialize() VelocityStateInitialize(); WaypointInitialize(); WaypointActiveInitialize(); - StatusVtolAutoTakeoffInitialize(); - StatusVtolLandInitialize(); pathPlannerHandle = PIOS_CALLBACKSCHEDULER_Create(&pathPlannerTask, CALLBACK_PRIORITY_REGULAR, TASK_PRIORITY, CALLBACKINFO_RUNNING_PATHPLANNER0, STACK_SIZE_BYTES); pathDesiredUpdaterHandle = PIOS_CALLBACKSCHEDULER_Create(&updatePathDesired, CALLBACK_PRIORITY_CRITICAL, TASK_PRIORITY, CALLBACKINFO_RUNNING_PATHPLANNER1, STACK_SIZE_BYTES); @@ -236,17 +229,17 @@ static void pathPlannerTask() return; } - // the transition from pathplanner to another flightmode back to pathplanner // triggers a reset back to 0 index in the waypoint list if (pathplanner_active == false) { - pathplanner_active = true; + pathplanner_active = true; - // This triggers callback to update variable - waypointActive.Index = 0; - WaypointActiveSet(&waypointActive); - - return; + FlightModeSettingsFlightModeChangeRestartsPathPlanOptions restart; + FlightModeSettingsFlightModeChangeRestartsPathPlanGet(&restart); + if (restart == FLIGHTMODESETTINGS_FLIGHTMODECHANGERESTARTSPATHPLAN_TRUE) { + setWaypoint(0); + return; + } } WaypointInstGet(waypointActive.Index, &waypoint); @@ -265,21 +258,6 @@ static void pathPlannerTask() return; } - // check start conditions - // autotakeoff requires midpoint thrust if we are in a pending takeoff situation - if (pathAction.Mode == PATHACTION_MODE_AUTOTAKEOFF) { - pathAction.EndCondition = PATHACTION_ENDCONDITION_LEGREMAINING; - if ((uint8_t)pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] == STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE) { - ManualControlCommandData cmd; - ManualControlCommandGet(&cmd); - if (cmd.Throttle > AUTOTAKEOFF_THROTTLE_LIMIT_TO_ALLOW_TAKEOFF_START) { - pathDesired.ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] = (float)STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_INITIATE; - PathDesiredSet(&pathDesired); - } - return; - } - } - // check if condition has been met endCondition = pathConditionCheck(); @@ -331,22 +309,45 @@ void updatePathDesired() WaypointActiveGet(&waypointActive); WaypointInstGet(waypointActive.Index, &waypoint); - // Capture if current mode is takeoff - bool autotakeoff = (pathAction.Mode == PATHACTION_MODE_AUTOTAKEOFF); - PathActionInstGet(waypoint.Action, &pathAction); PathDesiredData pathDesired; - switch (pathAction.Mode) { - case PATHACTION_MODE_AUTOTAKEOFF: - planner_setup_pathdesired_takeoff(&pathDesired); - break; - case PATHACTION_MODE_LAND: - planner_setup_pathdesired_land(&pathDesired); - break; - default: - planner_setup_pathdesired(&pathDesired, autotakeoff); - break; + + pathDesired.End.North = waypoint.Position.North; + pathDesired.End.East = waypoint.Position.East; + pathDesired.End.Down = waypoint.Position.Down; + pathDesired.EndingVelocity = waypoint.Velocity; + pathDesired.Mode = pathAction.Mode; + pathDesired.ModeParameters[0] = pathAction.ModeParameters[0]; + pathDesired.ModeParameters[1] = pathAction.ModeParameters[1]; + pathDesired.ModeParameters[2] = pathAction.ModeParameters[2]; + pathDesired.ModeParameters[3] = pathAction.ModeParameters[3]; + pathDesired.UID = waypointActive.Index; + + + if (waypointActive.Index == 0) { + PositionStateData positionState; + PositionStateGet(&positionState); + // First waypoint has itself as start point (used to be home position but that proved dangerous when looping) + + /*pathDesired.Start[PATHDESIRED_START_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; + pathDesired.Start[PATHDESIRED_START_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST]; + pathDesired.Start[PATHDESIRED_START_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN];*/ + // note: if certain flightmodes need to override Start, End or mode parameters, that should happen within + // the pathfollower as needed. This also holds if Start is replaced by current position for takeoff and landing + pathDesired.Start.North = positionState.North; + pathDesired.Start.East = positionState.East; + pathDesired.Start.Down = positionState.Down; + pathDesired.StartingVelocity = pathDesired.EndingVelocity; + } else { + // Get previous waypoint as start point + WaypointData waypointPrev; + WaypointInstGet(waypointActive.Index - 1, &waypointPrev); + + pathDesired.Start.North = waypointPrev.Position.North; + pathDesired.Start.East = waypointPrev.Position.East; + pathDesired.Start.Down = waypointPrev.Position.Down; + pathDesired.StartingVelocity = waypointPrev.Velocity; } PathDesiredSet(&pathDesired); @@ -437,112 +438,6 @@ void statusUpdated(__attribute__((unused)) UAVObjEvent *ev) PIOS_CALLBACKSCHEDULER_Dispatch(pathPlannerHandle); } -// Standard setup of a pathDesired command from the waypoint path plan -static void planner_setup_pathdesired(PathDesiredData *pathDesired, bool overwrite_start_position) -{ - pathDesired->End.North = waypoint.Position.North; - pathDesired->End.East = waypoint.Position.East; - pathDesired->End.Down = waypoint.Position.Down; - pathDesired->EndingVelocity = waypoint.Velocity; - pathDesired->Mode = pathAction.Mode; - pathDesired->ModeParameters[0] = pathAction.ModeParameters[0]; - pathDesired->ModeParameters[1] = pathAction.ModeParameters[1]; - pathDesired->ModeParameters[2] = pathAction.ModeParameters[2]; - pathDesired->ModeParameters[3] = pathAction.ModeParameters[3]; - pathDesired->UID = waypointActive.Index; - - - if (waypointActive.Index == 0 || overwrite_start_position) { - PositionStateData positionState; - PositionStateGet(&positionState); - // First waypoint has itself as start point (used to be home position but that proved dangerous when looping) - - /*pathDesired.Start[PATHDESIRED_START_NORTH] = waypoint.Position[WAYPOINT_POSITION_NORTH]; - pathDesired.Start[PATHDESIRED_START_EAST] = waypoint.Position[WAYPOINT_POSITION_EAST]; - pathDesired.Start[PATHDESIRED_START_DOWN] = waypoint.Position[WAYPOINT_POSITION_DOWN];*/ - // note takeoff relies on the start being the current location as it merely ascends and using - // the start as assumption current NE location - pathDesired->Start.North = positionState.North; - pathDesired->Start.East = positionState.East; - pathDesired->Start.Down = positionState.Down; - pathDesired->StartingVelocity = pathDesired->EndingVelocity; - } else { - // Get previous waypoint as start point - WaypointData waypointPrev; - WaypointInstGet(waypointActive.Index - 1, &waypointPrev); - - pathDesired->Start.North = waypointPrev.Position.North; - pathDesired->Start.East = waypointPrev.Position.East; - pathDesired->Start.Down = waypointPrev.Position.Down; - pathDesired->StartingVelocity = waypointPrev.Velocity; - } -} - -#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN 2.0f -#define AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX 50.0f -static void planner_setup_pathdesired_takeoff(PathDesiredData *pathDesired) -{ - PositionStateData positionState; - - PositionStateGet(&positionState); - float velocity_down; - float autotakeoff_height; - FlightModeSettingsAutoTakeOffVelocityGet(&velocity_down); - FlightModeSettingsAutoTakeOffHeightGet(&autotakeoff_height); - autotakeoff_height = fabsf(autotakeoff_height); - if (autotakeoff_height < AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN) { - autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MIN; - } else if (autotakeoff_height > AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX) { - autotakeoff_height = AUTOTAKEOFF_TO_INCREMENTAL_HEIGHT_MAX; - } - - - pathDesired->Start.North = positionState.North; - pathDesired->Start.East = positionState.East; - pathDesired->Start.Down = positionState.Down; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_NORTH] = 0.0f; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_EAST] = 0.0f; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_DOWN] = -velocity_down; - // initially halt takeoff. - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_AUTOTAKEOFF_CONTROLSTATE] = (float)STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_WAITFORMIDTHROTTLE; - - pathDesired->End.North = positionState.North; - pathDesired->End.East = positionState.East; - pathDesired->End.Down = positionState.Down - autotakeoff_height; - - pathDesired->StartingVelocity = 0.0f; - pathDesired->EndingVelocity = 0.0f; - pathDesired->Mode = PATHDESIRED_MODE_AUTOTAKEOFF; - - pathDesired->UID = waypointActive.Index; -} - -static void planner_setup_pathdesired_land(PathDesiredData *pathDesired) -{ - PositionStateData positionState; - - PositionStateGet(&positionState); - float velocity_down; - - FlightModeSettingsLandingVelocityGet(&velocity_down); - - pathDesired->Start.North = positionState.North; - pathDesired->Start.East = positionState.East; - pathDesired->Start.Down = positionState.Down; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_NORTH] = 0.0f; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_EAST] = 0.0f; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_VELOCITYVECTOR_DOWN] = velocity_down; - - pathDesired->End.North = positionState.North; - pathDesired->End.East = positionState.East; - pathDesired->End.Down = positionState.Down; - - pathDesired->StartingVelocity = 0.0f; - pathDesired->EndingVelocity = 0.0f; - pathDesired->Mode = PATHDESIRED_MODE_LAND; - pathDesired->ModeParameters[PATHDESIRED_MODEPARAMETER_LAND_OPTIONS] = (float)PATHDESIRED_MODEPARAMETER_LAND_OPTION_HORIZONTAL_PH; -} - // helper function to go to a specific waypoint static void setWaypoint(uint16_t num) diff --git a/shared/uavobjectdefinition/flightmodesettings.xml b/shared/uavobjectdefinition/flightmodesettings.xml index 162f96d6c..dbe2b72d4 100644 --- a/shared/uavobjectdefinition/flightmodesettings.xml +++ b/shared/uavobjectdefinition/flightmodesettings.xml @@ -87,6 +87,7 @@ + From c10717d3a23d9230203ec3a69b7460774382a49d Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Fri, 29 May 2015 21:39:00 +0200 Subject: [PATCH 11/58] OP-1900 get rid of highpower error by default again (too many false positives) --- shared/uavobjectdefinition/fixedwingpathfollowersettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml index 58f2b0d19..9d3e45f2c 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -46,7 +46,7 @@ + defaultvalue="1, 1.0, 0.5, 1.5, 1.0, 1, 0, 1, 1" /> From 23f9f4d9c9cd3d059b2bb211f06fb81d364e62b0 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 31 May 2015 11:17:49 +0200 Subject: [PATCH 12/58] OP-1900 add failsafe to FW pathfollower to fly safely without valid airspeed estimate --- .../PathFollower/fixedwingflycontroller.cpp | 238 ++++++++++-------- .../PathFollower/inc/fixedwingflycontroller.h | 1 + .../fixedwingpathfollowersettings.xml | 3 + .../fixedwingpathfollowerstatus.xml | 2 +- 4 files changed, 142 insertions(+), 102 deletions(-) diff --git a/flight/modules/PathFollower/fixedwingflycontroller.cpp b/flight/modules/PathFollower/fixedwingflycontroller.cpp index 3721fb1e1..432b97c4e 100644 --- a/flight/modules/PathFollower/fixedwingflycontroller.cpp +++ b/flight/modules/PathFollower/fixedwingflycontroller.cpp @@ -63,6 +63,7 @@ void FixedWingFlyController::Activate(void) SettingsUpdated(); resetGlobals(); mMode = pathDesired->Mode; + lastAirspeedUpdate = 0; } } @@ -227,10 +228,11 @@ void FixedWingFlyController::updatePathVelocity(float kFF, bool limited) */ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() { - uint8_t result = 1; - bool cutThrust = false; + uint8_t result = 1; + bool cutThrust = false; + bool hasAirspeed = true; - const float dT = fixedWingSettings->UpdatePeriod / 1000.0f; + const float dT = fixedWingSettings->UpdatePeriod / 1000.0f; VelocityDesiredData velocityDesired; VelocityStateData velocityState; @@ -243,7 +245,7 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() float groundspeedProjection; float indicatedAirspeedState; float indicatedAirspeedDesired; - float airspeedError; + float airspeedError = 0.0f; float pitchCommand; @@ -266,56 +268,99 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() AirspeedStateGet(&airspeedState); SystemSettingsGet(&systemSettings); + /** * Compute speed error and course */ - // missing sensors for airspeed-direction we have to assume within - // reasonable error that measured airspeed is actually the airspeed - // component in forward pointing direction - // airspeedVector is normalized - airspeedVector[0] = cos_lookup_deg(attitudeState.Yaw); - airspeedVector[1] = sin_lookup_deg(attitudeState.Yaw); - // current ground speed projected in forward direction - groundspeedProjection = velocityState.North * airspeedVector[0] + velocityState.East * airspeedVector[1]; - - // note that airspeedStateBias is ( calibratedAirspeed - groundspeedProjection ) at the time of measurement, - // but thanks to accelerometers, groundspeedProjection reacts faster to changes in direction - // than airspeed and gps sensors alone - indicatedAirspeedState = groundspeedProjection + indicatedAirspeedStateBias; - - // fluidMovement is a vector describing the aproximate movement vector of - // the surrounding fluid in 2d space (aka wind vector) - fluidMovement[0] = velocityState.North - (indicatedAirspeedState * airspeedVector[0]); - fluidMovement[1] = velocityState.East - (indicatedAirspeedState * airspeedVector[1]); - - // calculate the movement vector we need to fly to reach velocityDesired - - // taking fluidMovement into account - courseComponent[0] = velocityDesired.North - fluidMovement[0]; - courseComponent[1] = velocityDesired.East - fluidMovement[1]; - - indicatedAirspeedDesired = boundf(sqrtf(courseComponent[0] * courseComponent[0] + courseComponent[1] * courseComponent[1]), - fixedWingSettings->HorizontalVelMin, - fixedWingSettings->HorizontalVelMax); - - // if we could fly at arbitrary speeds, we'd just have to move towards the - // courseComponent vector as previously calculated and we'd be fine - // unfortunately however we are bound by min and max air speed limits, so - // we need to recalculate the correct course to meet at least the - // velocityDesired vector direction at our current speed - // this overwrites courseComponent - bool valid = correctCourse(courseComponent, (float *)&velocityDesired.North, fluidMovement, indicatedAirspeedDesired); - - // Error condition: wind speed too high, we can't go where we want anymore - fixedWingPathFollowerStatus.Errors.Wind = 0; - if ((!valid) && - fixedWingSettings->Safetymargins.Wind > 0.5f) { // alarm switched on - fixedWingPathFollowerStatus.Errors.Wind = 1; + // check for airspeed sensor + fixedWingPathFollowerStatus.Errors.AirspeedSensor = 0; + if (fixedWingSettings->UseAirspeedSensor == FIXEDWINGPATHFOLLOWERSETTINGS_USEAIRSPEEDSENSOR_FALSE) { + // fallback algo triggered voluntarily + hasAirspeed = false; + fixedWingPathFollowerStatus.Errors.AirspeedSensor = 1; + } else if (PIOS_DELAY_GetuSSince(lastAirspeedUpdate) > 1000000) { + // no airspeed update in one second, assume airspeed sensor failure + hasAirspeed = false; result = 0; + fixedWingPathFollowerStatus.Errors.AirspeedSensor = 1; } - // Airspeed error - airspeedError = indicatedAirspeedDesired - indicatedAirspeedState; + + if (hasAirspeed) { + // missing sensors for airspeed-direction we have to assume within + // reasonable error that measured airspeed is actually the airspeed + // component in forward pointing direction + // airspeedVector is normalized + airspeedVector[0] = cos_lookup_deg(attitudeState.Yaw); + airspeedVector[1] = sin_lookup_deg(attitudeState.Yaw); + + // current ground speed projected in forward direction + groundspeedProjection = velocityState.North * airspeedVector[0] + velocityState.East * airspeedVector[1]; + + // note that airspeedStateBias is ( calibratedAirspeed - groundspeedProjection ) at the time of measurement, + // but thanks to accelerometers, groundspeedProjection reacts faster to changes in direction + // than airspeed and gps sensors alone + indicatedAirspeedState = groundspeedProjection + indicatedAirspeedStateBias; + + // fluidMovement is a vector describing the aproximate movement vector of + // the surrounding fluid in 2d space (aka wind vector) + fluidMovement[0] = velocityState.North - (indicatedAirspeedState * airspeedVector[0]); + fluidMovement[1] = velocityState.East - (indicatedAirspeedState * airspeedVector[1]); + + // calculate the movement vector we need to fly to reach velocityDesired - + // taking fluidMovement into account + courseComponent[0] = velocityDesired.North - fluidMovement[0]; + courseComponent[1] = velocityDesired.East - fluidMovement[1]; + + indicatedAirspeedDesired = boundf(sqrtf(courseComponent[0] * courseComponent[0] + courseComponent[1] * courseComponent[1]), + fixedWingSettings->HorizontalVelMin, + fixedWingSettings->HorizontalVelMax); + + // if we could fly at arbitrary speeds, we'd just have to move towards the + // courseComponent vector as previously calculated and we'd be fine + // unfortunately however we are bound by min and max air speed limits, so + // we need to recalculate the correct course to meet at least the + // velocityDesired vector direction at our current speed + // this overwrites courseComponent + bool valid = correctCourse(courseComponent, (float *)&velocityDesired.North, fluidMovement, indicatedAirspeedDesired); + + // Error condition: wind speed too high, we can't go where we want anymore + fixedWingPathFollowerStatus.Errors.Wind = 0; + if ((!valid) && + fixedWingSettings->Safetymargins.Wind > 0.5f) { // alarm switched on + fixedWingPathFollowerStatus.Errors.Wind = 1; + result = 0; + } + + // Airspeed error + airspeedError = indicatedAirspeedDesired - indicatedAirspeedState; + + // Error condition: plane too slow or too fast + fixedWingPathFollowerStatus.Errors.Highspeed = 0; + fixedWingPathFollowerStatus.Errors.Lowspeed = 0; + if (indicatedAirspeedState > systemSettings.AirSpeedMax * fixedWingSettings->Safetymargins.Overspeed) { + fixedWingPathFollowerStatus.Errors.Overspeed = 1; + result = 0; + } + if (indicatedAirspeedState > fixedWingSettings->HorizontalVelMax * fixedWingSettings->Safetymargins.Highspeed) { + fixedWingPathFollowerStatus.Errors.Highspeed = 1; + result = 0; + cutThrust = true; + } + if (indicatedAirspeedState < fixedWingSettings->HorizontalVelMin * fixedWingSettings->Safetymargins.Lowspeed) { + fixedWingPathFollowerStatus.Errors.Lowspeed = 1; + result = 0; + } + if (indicatedAirspeedState < systemSettings.AirSpeedMin * fixedWingSettings->Safetymargins.Stallspeed) { + fixedWingPathFollowerStatus.Errors.Stallspeed = 1; + result = 0; + } + if (indicatedAirspeedState < fixedWingSettings->HorizontalVelMin * fixedWingSettings->Safetymargins.Lowspeed - fixedWingSettings->SafetyCutoffLimits.MaxDecelerationDeltaMPS) { + cutThrust = true; + result = 0; + } + } // Vertical speed error descentspeedDesired = boundf( @@ -324,41 +369,19 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() fixedWingSettings->VerticalVelMax); descentspeedError = descentspeedDesired - velocityState.Down; - // Error condition: plane too slow or too fast - fixedWingPathFollowerStatus.Errors.Highspeed = 0; - fixedWingPathFollowerStatus.Errors.Lowspeed = 0; - if (indicatedAirspeedState > systemSettings.AirSpeedMax * fixedWingSettings->Safetymargins.Overspeed) { - fixedWingPathFollowerStatus.Errors.Overspeed = 1; - result = 0; - } - if (indicatedAirspeedState > fixedWingSettings->HorizontalVelMax * fixedWingSettings->Safetymargins.Highspeed) { - fixedWingPathFollowerStatus.Errors.Highspeed = 1; - result = 0; - cutThrust = true; - } - if (indicatedAirspeedState < fixedWingSettings->HorizontalVelMin * fixedWingSettings->Safetymargins.Lowspeed) { - fixedWingPathFollowerStatus.Errors.Lowspeed = 1; - result = 0; - } - if (indicatedAirspeedState < systemSettings.AirSpeedMin * fixedWingSettings->Safetymargins.Stallspeed) { - fixedWingPathFollowerStatus.Errors.Stallspeed = 1; - result = 0; - } - if (indicatedAirspeedState < fixedWingSettings->HorizontalVelMin * fixedWingSettings->Safetymargins.Lowspeed - fixedWingSettings->SafetyCutoffLimits.MaxDecelerationDeltaMPS) { - cutThrust = true; - result = 0; - } - /** * Compute desired thrust command */ // Compute the cross feed from vertical speed to pitch, with saturation - float speedErrorToPowerCommandComponent = boundf( - (airspeedError / fixedWingSettings->HorizontalVelMin) * fixedWingSettings->AirspeedToPowerCrossFeed.Kp, - -fixedWingSettings->AirspeedToPowerCrossFeed.Max, - fixedWingSettings->AirspeedToPowerCrossFeed.Max - ); + float speedErrorToPowerCommandComponent = 0.0f; + if (hasAirspeed) { + speedErrorToPowerCommandComponent = boundf( + (airspeedError / fixedWingSettings->HorizontalVelMin) * fixedWingSettings->AirspeedToPowerCrossFeed.Kp, + -fixedWingSettings->AirspeedToPowerCrossFeed.Max, + fixedWingSettings->AirspeedToPowerCrossFeed.Max + ); + } // Compute final thrust response powerCommand = pid_apply(&PIDpower, -descentspeedError, dT) + @@ -404,34 +427,40 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() /** * Compute desired pitch command */ - // Compute the cross feed from vertical speed to pitch, with saturation - float verticalSpeedToPitchCommandComponent = boundf(-descentspeedError * fixedWingSettings->VerticalToPitchCrossFeed.Kp, - -fixedWingSettings->VerticalToPitchCrossFeed.Max, - fixedWingSettings->VerticalToPitchCrossFeed.Max - ); + if (hasAirspeed) { + // Compute the cross feed from vertical speed to pitch, with saturation + float verticalSpeedToPitchCommandComponent = boundf(-descentspeedError * fixedWingSettings->VerticalToPitchCrossFeed.Kp, + -fixedWingSettings->VerticalToPitchCrossFeed.Max, + fixedWingSettings->VerticalToPitchCrossFeed.Max + ); - // Compute the pitch command as err*Kp + errInt*Ki + X_feed. - pitchCommand = -pid_apply(&PIDspeed, airspeedError, dT) + verticalSpeedToPitchCommandComponent; + // Compute the pitch command as err*Kp + errInt*Ki + X_feed. + pitchCommand = -pid_apply(&PIDspeed, airspeedError, dT) + verticalSpeedToPitchCommandComponent; - fixedWingPathFollowerStatus.Error.Speed = airspeedError; - fixedWingPathFollowerStatus.ErrorInt.Speed = PIDspeed.iAccumulator; - fixedWingPathFollowerStatus.Command.Speed = pitchCommand; + fixedWingPathFollowerStatus.Error.Speed = airspeedError; + fixedWingPathFollowerStatus.ErrorInt.Speed = PIDspeed.iAccumulator; + fixedWingPathFollowerStatus.Command.Speed = pitchCommand; - stabDesired.Pitch = boundf(fixedWingSettings->PitchLimit.Neutral + pitchCommand, - fixedWingSettings->PitchLimit.Min, - fixedWingSettings->PitchLimit.Max); + stabDesired.Pitch = boundf(fixedWingSettings->PitchLimit.Neutral + pitchCommand, + fixedWingSettings->PitchLimit.Min, + fixedWingSettings->PitchLimit.Max); - // Error condition: high speed dive - fixedWingPathFollowerStatus.Errors.Pitchcontrol = 0; - if (fixedWingSettings->PitchLimit.Neutral + pitchCommand >= fixedWingSettings->PitchLimit.Max && // pitch demand is full up - velocityState.Down > 0.0f && // we ARE going down - descentspeedDesired < 0.0f && // we WANT to go up - airspeedError < 0.0f && // we are too fast already - fixedWingSettings->Safetymargins.Pitchcontrol > 0.5f) { // alarm switched on - fixedWingPathFollowerStatus.Errors.Pitchcontrol = 1; - result = 0; - cutThrust = true; + // Error condition: high speed dive + fixedWingPathFollowerStatus.Errors.Pitchcontrol = 0; + if (fixedWingSettings->PitchLimit.Neutral + pitchCommand >= fixedWingSettings->PitchLimit.Max && // pitch demand is full up + velocityState.Down > 0.0f && // we ARE going down + descentspeedDesired < 0.0f && // we WANT to go up + airspeedError < 0.0f && // we are too fast already + fixedWingSettings->Safetymargins.Pitchcontrol > 0.5f) { // alarm switched on + fixedWingPathFollowerStatus.Errors.Pitchcontrol = 1; + result = 0; + cutThrust = true; + } + } else { + // no airspeed sensor means we fly with constant pitch, like for landing pathfollower + stabDesired.Pitch = fixedWingSettings->LandingPitch; } + // Error condition: pitch way out of wack if (fixedWingSettings->Safetymargins.Pitchcontrol > 0.5f && (attitudeState.Pitch < fixedWingSettings->PitchLimit.Min - fixedWingSettings->SafetyCutoffLimits.PitchDeg || @@ -445,7 +474,12 @@ uint8_t FixedWingFlyController::updateFixedDesiredAttitude() /** * Compute desired roll command */ - courseError = RAD2DEG(atan2f(courseComponent[1], courseComponent[0])) - attitudeState.Yaw; + if (hasAirspeed) { + courseError = RAD2DEG(atan2f(courseComponent[1], courseComponent[0])) - attitudeState.Yaw; + } else { + // fallback based on effective movement direction when in fallback mode, hope that airspeed > wind velocity, or we will never get home + courseError = RAD2DEG(atan2f(velocityDesired.East, velocityDesired.North)) - RAD2DEG(atan2f(velocityState.East, velocityState.North)); + } if (courseError < -180.0f) { courseError += 360.0f; @@ -632,4 +666,6 @@ void FixedWingFlyController::AirspeedStateUpdatedCb(__attribute__((unused)) UAVO // changes to groundspeed to offset the airspeed by the same measurement. // This has a side effect that in the absence of any airspeed updates, the // pathfollower will fly using groundspeed. + + lastAirspeedUpdate = PIOS_DELAY_GetuS(); } diff --git a/flight/modules/PathFollower/inc/fixedwingflycontroller.h b/flight/modules/PathFollower/inc/fixedwingflycontroller.h index c79b0644c..a78c7c503 100644 --- a/flight/modules/PathFollower/inc/fixedwingflycontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingflycontroller.h @@ -70,6 +70,7 @@ private: void updatePathVelocity(float kFF, bool limited); uint8_t updateFixedDesiredAttitude(); bool correctCourse(float *C, float *V, float *F, float s); + int32_t lastAirspeedUpdate; struct pid PIDposH[2]; struct pid PIDposV; diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml index 9d3e45f2c..13b90f1f2 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -20,6 +20,9 @@ + + + diff --git a/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml b/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml index 2b2482de9..26fd4cdfc 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowerstatus.xml @@ -4,7 +4,7 @@ - + From 23dab7e0b650ebe6af98d1d5b4e8e9417716203a Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 4 Jun 2015 11:28:51 +0200 Subject: [PATCH 13/58] OP-1900 added deceleration check to autotakeoff failsafe --- .../modules/PathFollower/fixedwingautotakeoffcontroller.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp index d50d3318e..509805178 100644 --- a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp @@ -143,6 +143,10 @@ bool FixedWingAutoTakeoffController::isUnsafe(void) if (speed > maxVelocity) { maxVelocity = speed; } + // too much total deceleration (crash, insufficient climbing power, ...) + if (speed < maxVelocity - fixedWingSettings->SafetyCutoffLimits.MaxDecelerationDeltaMPS) { + abort = true; + } AttitudeStateData attitude; AttitudeStateGet(&attitude); // too much bank angle From cc3b10060f94b1061eb702aa67d8561e163f536a Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 4 Jun 2015 12:39:17 +0200 Subject: [PATCH 14/58] OP-1900 have path_progress updated correctly for leg_remaining and error_below end conditions to work in fixedwingautotakeoff --- .../fixedwingautotakeoffcontroller.cpp | 18 ++++++++++++++++++ .../PathFollower/fixedwinglandcontroller.cpp | 8 ++++++++ 2 files changed, 26 insertions(+) diff --git a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp index 509805178..80b72d40d 100644 --- a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp @@ -125,10 +125,22 @@ void FixedWingAutoTakeoffController::setAttitude(bool unsafe) StabilizationDesiredSet(&stabDesired); if (unsafe) { AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_WARNING); + pathStatus->Status = PATHSTATUS_STATUS_CRITICAL; } else { AlarmsSet(SYSTEMALARMS_ALARM_GUIDANCE, SYSTEMALARMS_ALARM_OK); } + // calculate fractional progress based on altitude + float downPos; + PositionStateDownGet(&downPos); + if (fabsf(pathDesired->End.Down - pathDesired->Start.Down) < 1e-3f) { + pathStatus->fractional_progress = 1.0f; + pathStatus->error = 0.0f; + } else { + pathStatus->fractional_progress = (downPos - pathDesired->Start.Down) / (pathDesired->End.Down - pathDesired->Start.Down); + } + pathStatus->error = fabsf(downPos - pathDesired->End.Down); + PathStatusSet(pathStatus); } @@ -178,6 +190,12 @@ void FixedWingAutoTakeoffController::init_launch(void) { // find out vector direction of *runway* (if any) // and align, otherwise just stay straight ahead + pathStatus->path_direction_north = 0.0f; + pathStatus->path_direction_east = 0.0f; + pathStatus->path_direction_down = 0.0f; + pathStatus->correction_direction_north = 0.0f; + pathStatus->correction_direction_east = 0.0f; + pathStatus->correction_direction_down = 0.0f; if (fabsf(pathDesired->Start.North - pathDesired->End.North) < 1e-3f && fabsf(pathDesired->Start.East - pathDesired->End.East) < 1e-3f) { AttitudeStateYawGet(&initYaw); diff --git a/flight/modules/PathFollower/fixedwinglandcontroller.cpp b/flight/modules/PathFollower/fixedwinglandcontroller.cpp index 52727eceb..d11d4c4fe 100644 --- a/flight/modules/PathFollower/fixedwinglandcontroller.cpp +++ b/flight/modules/PathFollower/fixedwinglandcontroller.cpp @@ -103,6 +103,14 @@ int32_t FixedWingLandController::Initialize(FixedWingPathFollowerSettingsData *p void FixedWingLandController::resetGlobals() { pathStatus->path_time = 0.0f; + pathStatus->path_direction_north = 0.0f; + pathStatus->path_direction_east = 0.0f; + pathStatus->path_direction_down = 0.0f; + pathStatus->correction_direction_north = 0.0f; + pathStatus->correction_direction_east = 0.0f; + pathStatus->correction_direction_down = 0.0f; + pathStatus->error = 0.0f; + pathStatus->fractional_progress = 0.0f; } /** From ffe9dde8d077ee861aab6fe7c8b587731ad7abd5 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Thu, 4 Jun 2015 13:21:13 +0200 Subject: [PATCH 15/58] =?UTF-8?q?OP-1900=20changed=20default=20landing=20p?= =?UTF-8?q?itch=20from=2015=20=C2=B0=20pitch=20up=20to=207.5=C2=B0=20-=201?= =?UTF-8?q?5=20is=20too=20high=20and=20leads=20to=20stall=20on=20some=20fr?= =?UTF-8?q?ames?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- shared/uavobjectdefinition/fixedwingpathfollowersettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml index 13b90f1f2..68b0a406e 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -63,7 +63,7 @@ - + From 91a9c19e1f14ff3df8a1fba280bddee56c76ed72 Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Thu, 21 Apr 2016 13:22:03 +0200 Subject: [PATCH 16/58] LP-293 Implemented AlarmString() function to return human readable SystemAlarms data --- flight/libraries/alarms.c | 104 ++++++++++++++++++++++++++++++++++ flight/libraries/inc/alarms.h | 2 + 2 files changed, 106 insertions(+) diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index db555ad8e..c4d8963be 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -37,6 +37,8 @@ #define PIOS_ALARM_GRACETIME 1000 #endif // PIOS_ALARM_GRACETIME +#define NELEM(x) ((sizeof(x) / sizeof((x)[0]))) + // Private types // Private variables @@ -281,6 +283,108 @@ SystemAlarmsAlarmOptions AlarmsGetHighestSeverity() return highest; } + +static const char *const systemalarms_severity_names[] = { + [SYSTEMALARMS_ALARM_UNINITIALISED] = "UNINITIALISED", + [SYSTEMALARMS_ALARM_OK] = "OK", + [SYSTEMALARMS_ALARM_WARNING] = "WARNING", + [SYSTEMALARMS_ALARM_CRITICAL] = "CRITICAL", + [SYSTEMALARMS_ALARM_ERROR] = "ERROR" +}; + +static const char *const systemalarms_alarm_names[] = { + [SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION] = "CONFIG", + [SYSTEMALARMS_ALARM_BOOTFAULT] = "BOOT", + [SYSTEMALARMS_ALARM_OUTOFMEMORY] = "MEMORY", + [SYSTEMALARMS_ALARM_STACKOVERFLOW] = "STACK", + [SYSTEMALARMS_ALARM_CPUOVERLOAD] = "CPU", + [SYSTEMALARMS_ALARM_EVENTSYSTEM] = "EVENTSYSTEM", + [SYSTEMALARMS_ALARM_TELEMETRY] = "TELEMETRY", + [SYSTEMALARMS_ALARM_RECEIVER] = "RECEIVER", + [SYSTEMALARMS_ALARM_MANUALCONTROL] = "MANUAL", + [SYSTEMALARMS_ALARM_ACTUATOR] = "ACTUATOR", + [SYSTEMALARMS_ALARM_ATTITUDE] = "ATTITUDE", + [SYSTEMALARMS_ALARM_SENSORS] = "SENSORS", + [SYSTEMALARMS_ALARM_MAGNETOMETER] = "MAG", + [SYSTEMALARMS_ALARM_AIRSPEED] = "AIRSPEED", + [SYSTEMALARMS_ALARM_STABILIZATION] = "STAB", + [SYSTEMALARMS_ALARM_GUIDANCE] = "GUIDANCE", + [SYSTEMALARMS_ALARM_PATHPLAN] = "PLAN", + [SYSTEMALARMS_ALARM_BATTERY] = "BATTERY", + [SYSTEMALARMS_ALARM_FLIGHTTIME] = "TIME", + [SYSTEMALARMS_ALARM_I2C] = "I2C", + [SYSTEMALARMS_ALARM_GPS] = "GPS", +}; + +static const char *const systemalarms_extendedalarmstatus_names[] = { + [SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED] = "CFG:REBOOT", + [SYSTEMALARMS_EXTENDEDALARMSTATUS_FLIGHTMODE] = "CFG:FLIGHTMODE", + [SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT] = "CFG:ONESHOT", + [SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE] = "CFG:THR-COL", +}; + +static const SystemAlarmsAlarmOptions severity_order[] = { + SYSTEMALARMS_ALARM_CRITICAL, SYSTEMALARMS_ALARM_WARNING, SYSTEMALARMS_ALARM_ERROR +}; + +size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size) +{ + size_t bytes_written = 0; + + PIOS_STATIC_ASSERT(NELEM(systemalarms_alarm_names) == SYSTEMALARMS_ALARM_NUMELEM); + + for (unsigned order = 0; order < NELEM(severity_order); ++order) { + // should we prepend severity level here? No, not for now. + + for (unsigned i = 0; i < SYSTEMALARMS_ALARM_NUMELEM; ++i) { + if ((SystemAlarmsAlarmToArray(alarm->Alarm)[i] == severity_order[order]) + && (systemalarms_alarm_names[i])) { + // in which case should we dig into extended alarm status? + // looks like SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION sets most of the extended alarms + // except SYSTEMALARMS_ALARM_BOOTFAULT which also sets SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED + + const char *current_msg = systemalarms_alarm_names[i]; + + switch (i) { + case SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION: + if (alarm->ExtendedAlarmStatus.SystemConfiguration < NELEM(systemalarms_extendedalarmstatus_names)) { + current_msg = systemalarms_extendedalarmstatus_names[alarm->ExtendedAlarmStatus.SystemConfiguration]; + } + break; + + case SYSTEMALARMS_ALARM_BOOTFAULT: + if (alarm->ExtendedAlarmStatus.BootFault < NELEM(systemalarms_extendedalarmstatus_names)) { + current_msg = systemalarms_extendedalarmstatus_names[alarm->ExtendedAlarmStatus.BootFault]; + } + break; + + default:; + } + + int current_len = strlen(current_msg); + + if ((bytes_written + current_len + 2) >= buffer_size) { + break; + } + + memcpy(buffer + bytes_written, current_msg, current_len); + + bytes_written += current_len; + + buffer[bytes_written++] = ' '; + } + } + } + + if (bytes_written > 0) { + --bytes_written; // get rid of that trailing space. + } + + buffer[bytes_written] = 0; + + return bytes_written; +} + /** * @} * @} diff --git a/flight/libraries/inc/alarms.h b/flight/libraries/inc/alarms.h index 304916dbc..4492216b0 100644 --- a/flight/libraries/inc/alarms.h +++ b/flight/libraries/inc/alarms.h @@ -48,6 +48,8 @@ int32_t AlarmsHasErrors(); int32_t AlarmsHasCritical(); SystemAlarmsAlarmOptions AlarmsGetHighestSeverity(); +size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size); + #endif // ALARMS_H /** From e513db4b4da9741d129712afdd28279508621408 Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Thu, 21 Apr 2016 13:42:06 +0200 Subject: [PATCH 17/58] LP-293 Added state parameter to receive highest severity level. --- flight/libraries/alarms.c | 7 ++++++- flight/libraries/inc/alarms.h | 2 +- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index c4d8963be..4aa9b1536 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -327,7 +327,7 @@ static const SystemAlarmsAlarmOptions severity_order[] = { SYSTEMALARMS_ALARM_CRITICAL, SYSTEMALARMS_ALARM_WARNING, SYSTEMALARMS_ALARM_ERROR }; -size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size) +size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, SystemAlarmsAlarmOptions *state) { size_t bytes_written = 0; @@ -339,6 +339,11 @@ size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size) for (unsigned i = 0; i < SYSTEMALARMS_ALARM_NUMELEM; ++i) { if ((SystemAlarmsAlarmToArray(alarm->Alarm)[i] == severity_order[order]) && (systemalarms_alarm_names[i])) { + if (state) { // they are already sorted by severity as we are processing in specific order + *state = severity_order[order]; + state = 0; + } + // in which case should we dig into extended alarm status? // looks like SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION sets most of the extended alarms // except SYSTEMALARMS_ALARM_BOOTFAULT which also sets SYSTEMALARMS_EXTENDEDALARMSTATUS_REBOOTREQUIRED diff --git a/flight/libraries/inc/alarms.h b/flight/libraries/inc/alarms.h index 4492216b0..408861930 100644 --- a/flight/libraries/inc/alarms.h +++ b/flight/libraries/inc/alarms.h @@ -48,7 +48,7 @@ int32_t AlarmsHasErrors(); int32_t AlarmsHasCritical(); SystemAlarmsAlarmOptions AlarmsGetHighestSeverity(); -size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size); +size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, SystemAlarmsAlarmOptions *state); #endif // ALARMS_H From 8f937e0508d7e57195f602849402c8c58fa33ade Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Thu, 21 Apr 2016 14:17:10 +0200 Subject: [PATCH 18/58] LP-293 Changed alarm strings to match GCS display --- flight/libraries/alarms.c | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index 4aa9b1536..b11a133f2 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -295,22 +295,22 @@ static const char *const systemalarms_severity_names[] = { static const char *const systemalarms_alarm_names[] = { [SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION] = "CONFIG", [SYSTEMALARMS_ALARM_BOOTFAULT] = "BOOT", - [SYSTEMALARMS_ALARM_OUTOFMEMORY] = "MEMORY", + [SYSTEMALARMS_ALARM_OUTOFMEMORY] = "MEM", [SYSTEMALARMS_ALARM_STACKOVERFLOW] = "STACK", [SYSTEMALARMS_ALARM_CPUOVERLOAD] = "CPU", - [SYSTEMALARMS_ALARM_EVENTSYSTEM] = "EVENTSYSTEM", + [SYSTEMALARMS_ALARM_EVENTSYSTEM] = "EVENT", [SYSTEMALARMS_ALARM_TELEMETRY] = "TELEMETRY", - [SYSTEMALARMS_ALARM_RECEIVER] = "RECEIVER", + [SYSTEMALARMS_ALARM_RECEIVER] = "INPUT", [SYSTEMALARMS_ALARM_MANUALCONTROL] = "MANUAL", [SYSTEMALARMS_ALARM_ACTUATOR] = "ACTUATOR", - [SYSTEMALARMS_ALARM_ATTITUDE] = "ATTITUDE", - [SYSTEMALARMS_ALARM_SENSORS] = "SENSORS", + [SYSTEMALARMS_ALARM_ATTITUDE] = "ATTI", + [SYSTEMALARMS_ALARM_SENSORS] = "SENSOR", [SYSTEMALARMS_ALARM_MAGNETOMETER] = "MAG", - [SYSTEMALARMS_ALARM_AIRSPEED] = "AIRSPEED", + [SYSTEMALARMS_ALARM_AIRSPEED] = "AIRSPD", [SYSTEMALARMS_ALARM_STABILIZATION] = "STAB", [SYSTEMALARMS_ALARM_GUIDANCE] = "GUIDANCE", [SYSTEMALARMS_ALARM_PATHPLAN] = "PLAN", - [SYSTEMALARMS_ALARM_BATTERY] = "BATTERY", + [SYSTEMALARMS_ALARM_BATTERY] = "BATT", [SYSTEMALARMS_ALARM_FLIGHTTIME] = "TIME", [SYSTEMALARMS_ALARM_I2C] = "I2C", [SYSTEMALARMS_ALARM_GPS] = "GPS", @@ -376,13 +376,13 @@ size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, Sy bytes_written += current_len; - buffer[bytes_written++] = ' '; + buffer[bytes_written++] = ','; } } } if (bytes_written > 0) { - --bytes_written; // get rid of that trailing space. + --bytes_written; // get rid of that trailing separator. } buffer[bytes_written] = 0; From 72582d1100c45aa1e784bf769902c5dd6f1685db Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Thu, 21 Apr 2016 23:59:23 +0200 Subject: [PATCH 19/58] LP-293 Added severity level parameter to AlarmString(). Reverted alarm sort order to natural severity levels (highest to lowest): ERROR, CRITICAL, WARNING, OK --- flight/libraries/alarms.c | 16 ++++++---------- flight/libraries/inc/alarms.h | 2 +- 2 files changed, 7 insertions(+), 11 deletions(-) diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index b11a133f2..8ba2820a7 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -323,25 +323,21 @@ static const char *const systemalarms_extendedalarmstatus_names[] = { [SYSTEMALARMS_EXTENDEDALARMSTATUS_BADTHROTTLEORCOLLECTIVEINPUTRANGE] = "CFG:THR-COL", }; -static const SystemAlarmsAlarmOptions severity_order[] = { - SYSTEMALARMS_ALARM_CRITICAL, SYSTEMALARMS_ALARM_WARNING, SYSTEMALARMS_ALARM_ERROR -}; - -size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, SystemAlarmsAlarmOptions *state) +size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, SystemAlarmsAlarmOptions level, SystemAlarmsAlarmOptions *highestSeverity) { size_t bytes_written = 0; PIOS_STATIC_ASSERT(NELEM(systemalarms_alarm_names) == SYSTEMALARMS_ALARM_NUMELEM); - for (unsigned order = 0; order < NELEM(severity_order); ++order) { + for (unsigned severity = SYSTEMALARMS_ALARM_ERROR; severity >= level; --severity) { // should we prepend severity level here? No, not for now. for (unsigned i = 0; i < SYSTEMALARMS_ALARM_NUMELEM; ++i) { - if ((SystemAlarmsAlarmToArray(alarm->Alarm)[i] == severity_order[order]) + if ((SystemAlarmsAlarmToArray(alarm->Alarm)[i] == severity) && (systemalarms_alarm_names[i])) { - if (state) { // they are already sorted by severity as we are processing in specific order - *state = severity_order[order]; - state = 0; + if (highestSeverity) { // they are already sorted by severity as we are processing in specific order + *highestSeverity = severity; + highestSeverity = 0; } // in which case should we dig into extended alarm status? diff --git a/flight/libraries/inc/alarms.h b/flight/libraries/inc/alarms.h index 408861930..4afbc6146 100644 --- a/flight/libraries/inc/alarms.h +++ b/flight/libraries/inc/alarms.h @@ -48,7 +48,7 @@ int32_t AlarmsHasErrors(); int32_t AlarmsHasCritical(); SystemAlarmsAlarmOptions AlarmsGetHighestSeverity(); -size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, SystemAlarmsAlarmOptions *state); +size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, SystemAlarmsAlarmOptions level, SystemAlarmsAlarmOptions *highestSeverity); #endif // ALARMS_H From 96ce3db02d8f33fbc04a27e3e0ac7c5605e97e00 Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Fri, 22 Apr 2016 02:04:21 +0200 Subject: [PATCH 20/58] LP-293 Added LibrePilot to @author tag --- flight/libraries/alarms.c | 3 ++- flight/libraries/inc/alarms.h | 3 ++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index 8ba2820a7..bd049a7a2 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -6,7 +6,8 @@ * @brief OpenPilot System libraries are available to all OP modules. * @{ * @file alarms.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Library for setting and clearing system alarms * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/libraries/inc/alarms.h b/flight/libraries/inc/alarms.h index 4afbc6146..afcbfac24 100644 --- a/flight/libraries/inc/alarms.h +++ b/flight/libraries/inc/alarms.h @@ -5,7 +5,8 @@ * @addtogroup OpenPilotLibraries OpenPilot System Libraries * @{ * @file alarms.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Include file of the alarm library * @see The GNU Public License (GPL) Version 3 * From 85fa65a514c7a8528345074f186812d9b943c0dc Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Fri, 22 Apr 2016 22:47:25 +0200 Subject: [PATCH 21/58] LP-293 Fixed remaining buffer space calculation. Changed name of position variable to less misleading. --- flight/libraries/alarms.c | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index bd049a7a2..772af3da0 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -326,7 +326,7 @@ static const char *const systemalarms_extendedalarmstatus_names[] = { size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, SystemAlarmsAlarmOptions level, SystemAlarmsAlarmOptions *highestSeverity) { - size_t bytes_written = 0; + size_t pos = 0; PIOS_STATIC_ASSERT(NELEM(systemalarms_alarm_names) == SYSTEMALARMS_ALARM_NUMELEM); @@ -359,32 +359,30 @@ size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, Sy current_msg = systemalarms_extendedalarmstatus_names[alarm->ExtendedAlarmStatus.BootFault]; } break; - - default:; } int current_len = strlen(current_msg); - - if ((bytes_written + current_len + 2) >= buffer_size) { + + if ((pos + current_len + 1) > buffer_size) { break; } - memcpy(buffer + bytes_written, current_msg, current_len); + memcpy(buffer + pos, current_msg, current_len); - bytes_written += current_len; + pos += current_len; - buffer[bytes_written++] = ','; + buffer[pos++] = ','; } } } - if (bytes_written > 0) { - --bytes_written; // get rid of that trailing separator. + if (pos > 0) { + --pos; // get rid of that trailing separator. } - buffer[bytes_written] = 0; + buffer[pos] = 0; - return bytes_written; + return pos; // return length of the string in buffer. Actual bytes written is +1 } /** From e550317fdf74c940ffa2c10af7546ad22719b7ad Mon Sep 17 00:00:00 2001 From: Mateusz Kaduk Date: Sun, 10 Apr 2016 18:46:40 +0200 Subject: [PATCH 22/58] LP-286 Port TauLabs filter in UAVobjectbrowser --- .../streamservice/streamserviceplugin.h | 2 +- .../uavobjectbrowser/browseritemdelegate.cpp | 32 ++- .../uavobjectbrowser/browseritemdelegate.h | 10 +- .../uavobjectbrowser/uavobjectbrowser.ui | 35 ++++ .../uavobjectbrowserwidget.cpp | 193 ++++++++++++++---- .../uavobjectbrowser/uavobjectbrowserwidget.h | 19 +- .../uavobjectbrowser/uavobjecttreemodel.h | 2 +- 7 files changed, 243 insertions(+), 50 deletions(-) diff --git a/ground/gcs/src/plugins/streamservice/streamserviceplugin.h b/ground/gcs/src/plugins/streamservice/streamserviceplugin.h index b17f49789..2a628b7d7 100644 --- a/ground/gcs/src/plugins/streamservice/streamserviceplugin.h +++ b/ground/gcs/src/plugins/streamservice/streamserviceplugin.h @@ -37,7 +37,7 @@ class QTcpSocket; class StreamServicePlugin : public ExtensionSystem::IPlugin { Q_OBJECT - Q_PLUGIN_METADATA(IID "Openpilot.StreamService") + Q_PLUGIN_METADATA(IID "Openpilot.StreamService") public: StreamServicePlugin(); diff --git a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp index 028dc82c3..6fddafa1d 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp @@ -2,7 +2,8 @@ ****************************************************************************** * * @file browseritemdelegate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup UAVObjectBrowserPlugin UAVObject Browser Plugin @@ -25,41 +26,52 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "uavobjectbrowserwidget.h" #include "browseritemdelegate.h" #include "fieldtreeitem.h" -BrowserItemDelegate::BrowserItemDelegate(QObject *parent) : +BrowserItemDelegate::BrowserItemDelegate(TreeSortFilterProxyModel *proxyModel, QObject *parent) : QStyledItemDelegate(parent) -{} +{ + this->proxyModel = proxyModel; +} QWidget *BrowserItemDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem & option, - const QModelIndex & index) const + const QModelIndex & proxyIndex) const { Q_UNUSED(option) - FieldTreeItem * item = static_cast(index.internalPointer()); - QWidget *editor = item->createEditor(parent); + QModelIndex index = proxyModel->mapToSource(proxyIndex); + + FieldTreeItem *item = static_cast(index.internalPointer()); + QWidget *editor = item->createEditor(parent); Q_ASSERT(editor); return editor; } void BrowserItemDelegate::setEditorData(QWidget *editor, - const QModelIndex &index) const + const QModelIndex & proxyIndex) const { + QModelIndex index = proxyModel->mapToSource(proxyIndex); + FieldTreeItem *item = static_cast(index.internalPointer()); - QVariant value = index.model()->data(index, Qt::EditRole); + QVariant value = proxyIndex.model()->data(proxyIndex, Qt::EditRole); item->setEditorValue(editor, value); } void BrowserItemDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, - const QModelIndex &index) const + const QModelIndex &proxyIndex) const { + QModelIndex index = proxyModel->mapToSource(proxyIndex); + FieldTreeItem *item = static_cast(index.internalPointer()); QVariant value = item->getEditorValue(editor); - model->setData(index, value, Qt::EditRole); + bool ret = model->setData(proxyIndex, value, Qt::EditRole); + + Q_ASSERT(ret); } void BrowserItemDelegate::updateEditorGeometry(QWidget *editor, diff --git a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h index 17952b5db..2605db7dc 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h @@ -2,7 +2,8 @@ ****************************************************************************** * * @file browseritemdelegate.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup UAVObjectBrowserPlugin UAVObject Browser Plugin @@ -30,10 +31,12 @@ #include +class TreeSortFilterProxyModel; + class BrowserItemDelegate : public QStyledItemDelegate { Q_OBJECT public: - explicit BrowserItemDelegate(QObject *parent = 0); + explicit BrowserItemDelegate(TreeSortFilterProxyModel *proxyModel, QObject *parent = 0); QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const; @@ -51,6 +54,9 @@ public: signals: public slots: + +private: + TreeSortFilterProxyModel *proxyModel; }; #endif // BROWSERITEMDELEGATE_H diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui index 492ab119f..5feed5889 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui @@ -204,6 +204,40 @@ + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 10 + 20 + + + + + + + + Search for UAVObject... + + + + + + + Clear + + + + .. + + + @@ -273,6 +307,7 @@ This space shows a description of the selected UAVObject. + diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index cea702e25..59efba6e1 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -2,7 +2,8 @@ ****************************************************************************** * * @file uavobjectbrowserwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup UAVObjectBrowserPlugin UAVObject Browser Plugin @@ -49,10 +50,13 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent m_viewoptions->setupUi(m_viewoptionsDialog); m_browser->setupUi(this); m_model = new UAVObjectTreeModel(); - m_browser->treeView->setModel(m_model); + m_modelProxy = new TreeSortFilterProxyModel(this); + m_modelProxy->setSourceModel(m_model); + m_modelProxy->setDynamicSortFilter(true); + m_browser->treeView->setModel(m_modelProxy); m_browser->treeView->setColumnWidth(0, 300); - BrowserItemDelegate *m_delegate = new BrowserItemDelegate(); + BrowserItemDelegate *m_delegate = new BrowserItemDelegate(m_modelProxy); m_browser->treeView->setItemDelegate(m_delegate); m_browser->treeView->setEditTriggers(QAbstractItemView::AllEditTriggers); m_browser->treeView->setSelectionBehavior(QAbstractItemView::SelectItems); @@ -76,6 +80,8 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); connect(m_viewoptions->cbDescription, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); connect(m_browser->splitter, SIGNAL(splitterMoved(int, int)), this, SLOT(splitterMoved())); + connect(m_browser->searchLine, SIGNAL(textChanged(QString)), this, SLOT(searchLineChanged(QString))); + connect(m_browser->searchClearButton, SIGNAL(clicked(bool)), this, SLOT(searchTextCleared())); enableSendRequest(false); } @@ -97,11 +103,29 @@ void UAVObjectBrowserWidget::setSplitterState(QByteArray state) m_browser->splitter->restoreState(state); } + +void UAVObjectBrowserWidget::resetProxyModel(UAVObjectTreeModel *currentModel) +{ + m_modelProxy = new TreeSortFilterProxyModel(this); + m_modelProxy->setSourceModel(currentModel); + m_modelProxy->setDynamicSortFilter(true); + m_browser->treeView->setModel(m_modelProxy); + + BrowserItemDelegate *m_delegate = new BrowserItemDelegate(m_modelProxy); + m_browser->treeView->setItemDelegate(m_delegate); + + if (!m_browser->searchLine->text().isEmpty()) { + emit searchLineChanged(m_browser->searchLine->text()); + } +} + void UAVObjectBrowserWidget::showMetaData(bool show) { QList metaIndexes = m_model->getMetaDataIndexes(); - foreach(QModelIndex index, metaIndexes) { - m_browser->treeView->setRowHidden(index.row(), index.parent(), !show); + foreach(QModelIndex modelIndex, metaIndexes) { + QModelIndex proxyModelindex = m_modelProxy->mapFromSource(modelIndex); + + m_browser->treeView->setRowHidden(proxyModelindex.row(), proxyModelindex.parent(), !show); } } @@ -115,12 +139,12 @@ void UAVObjectBrowserWidget::categorize(bool categorize) UAVObjectTreeModel *tmpModel = m_model; m_model = new UAVObjectTreeModel(0, categorize, m_viewoptions->cbScientific->isChecked()); + resetProxyModel(m_model); m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); m_model->setManuallyChangedColor(m_manuallyChangedColor); m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); m_model->setOnlyHilightChangedValues(m_onlyHilightChangedValues); m_model->setUnknowObjectColor(m_unknownObjectColor); - m_browser->treeView->setModel(m_model); showMetaData(m_viewoptions->cbMetaData->isChecked()); connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection); @@ -132,11 +156,10 @@ void UAVObjectBrowserWidget::useScientificNotation(bool scientific) UAVObjectTreeModel *tmpModel = m_model; m_model = new UAVObjectTreeModel(0, m_viewoptions->cbCategorized->isChecked(), scientific); - m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); + resetProxyModel(m_model); m_model->setManuallyChangedColor(m_manuallyChangedColor); m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); m_model->setUnknowObjectColor(m_unknownObjectColor); - m_browser->treeView->setModel(m_model); showMetaData(m_viewoptions->cbMetaData->isChecked()); connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection); @@ -147,26 +170,28 @@ void UAVObjectBrowserWidget::sendUpdate() { this->setFocus(); ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); - objItem->apply(); - UAVObject *obj = objItem->object(); - Q_ASSERT(obj); - obj->updated(); + if (objItem != NULL) { + objItem->apply(); + UAVObject *obj = objItem->object(); + Q_ASSERT(obj); + obj->updated(); + } } void UAVObjectBrowserWidget::requestUpdate() { ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); - UAVObject *obj = objItem->object(); - Q_ASSERT(obj); - obj->requestUpdate(); + if (objItem != NULL) { + UAVObject *obj = objItem->object(); + Q_ASSERT(obj); + obj->requestUpdate(); + } } ObjectTreeItem *UAVObjectBrowserWidget::findCurrentObjectTreeItem() { - QModelIndex current = m_browser->treeView->currentIndex(); + QModelIndex current = m_modelProxy->mapToSource(m_browser->treeView->currentIndex()); TreeItem *item = static_cast(current.internalPointer()); ObjectTreeItem *objItem = 0; @@ -196,12 +221,14 @@ void UAVObjectBrowserWidget::saveObject() this->setFocus(); // Send update so that the latest value is saved sendUpdate(); + // Save object ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); - UAVObject *obj = objItem->object(); - Q_ASSERT(obj); - updateObjectPersistance(ObjectPersistence::OPERATION_SAVE, obj); + if (objItem != NULL) { + UAVObject *obj = objItem->object(); + Q_ASSERT(obj); + updateObjectPersistance(ObjectPersistence::OPERATION_SAVE, obj); + } } void UAVObjectBrowserWidget::loadObject() @@ -209,22 +236,24 @@ void UAVObjectBrowserWidget::loadObject() // Load object ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); - UAVObject *obj = objItem->object(); - Q_ASSERT(obj); - updateObjectPersistance(ObjectPersistence::OPERATION_LOAD, obj); - // Retrieve object so that latest value is displayed - requestUpdate(); + if (objItem != NULL) { + UAVObject *obj = objItem->object(); + Q_ASSERT(obj); + updateObjectPersistance(ObjectPersistence::OPERATION_LOAD, obj); + // Retrieve object so that latest value is displayed + requestUpdate(); + } } void UAVObjectBrowserWidget::eraseObject() { ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); - UAVObject *obj = objItem->object(); - Q_ASSERT(obj); - updateObjectPersistance(ObjectPersistence::OPERATION_DELETE, obj); + if (objItem != NULL) { + UAVObject *obj = objItem->object(); + Q_ASSERT(obj); + updateObjectPersistance(ObjectPersistence::OPERATION_DELETE, obj); + } } void UAVObjectBrowserWidget::updateObjectPersistance(ObjectPersistence::OperationOptions op, UAVObject *obj) @@ -248,9 +277,11 @@ void UAVObjectBrowserWidget::currentChanged(const QModelIndex ¤t, const QM { Q_UNUSED(previous); - TreeItem *item = static_cast(current.internalPointer()); - bool enable = true; - if (current == QModelIndex()) { + QModelIndex cindex = m_modelProxy->mapToSource(current); + + TreeItem *item = static_cast(cindex.internalPointer()); + bool enable = true; + if (cindex == QModelIndex()) { enable = false; } TopTreeItem *top = dynamic_cast(item); @@ -388,3 +419,95 @@ void UAVObjectBrowserWidget::updateDescription() } m_browser->descriptionText->setText(""); } + +/** + * @brief UAVObjectBrowserWidget::searchTextChanged Looks for matching text in the UAVO fields + */ + +void UAVObjectBrowserWidget::searchLineChanged(QString searchText) +{ + m_modelProxy->setFilterRegExp(QRegExp(searchText, Qt::CaseInsensitive, QRegExp::FixedString)); + showMetaData(m_viewoptions->cbMetaData->isChecked()); + if (!searchText.isEmpty()) { + m_browser->treeView->expandAll(); + } else { + m_browser->treeView->collapseAll(); + } +} + +void UAVObjectBrowserWidget::searchTextCleared() +{ + m_browser->searchLine->clear(); +} + +TreeSortFilterProxyModel::TreeSortFilterProxyModel(QObject *p) : + QSortFilterProxyModel(p) +{ + Q_ASSERT(p); +} + +/** + * @brief TreeSortFilterProxyModel::filterAcceptsRow Taken from + * http://qt-project.org/forums/viewthread/7782. This proxy model + * will accept rows: + * - That match themselves, or + * - That have a parent that matches (on its own), or + * - That have a child that matches. + * @param sourceRow + * @param sourceParent + * @return + */ +bool TreeSortFilterProxyModel::filterAcceptsRow(int source_row, const QModelIndex &source_parent) const +{ + if (filterAcceptsRowItself(source_row, source_parent)) { + return true; + } + + // accept if any of the parents is accepted on it's own merits + QModelIndex parent = source_parent; + while (parent.isValid()) { + if (filterAcceptsRowItself(parent.row(), parent.parent())) { + return true; + } + parent = parent.parent(); + } + + // accept if any of the children is accepted on it's own merits + if (hasAcceptedChildren(source_row, source_parent)) { + return true; + } + + return false; +} + +bool TreeSortFilterProxyModel::filterAcceptsRowItself(int source_row, const QModelIndex &source_parent) const +{ + return QSortFilterProxyModel::filterAcceptsRow(source_row, source_parent); +} + +bool TreeSortFilterProxyModel::hasAcceptedChildren(int source_row, const QModelIndex &source_parent) const +{ + QModelIndex item = sourceModel()->index(source_row, 0, source_parent); + + if (!item.isValid()) { + return false; + } + + // check if there are children + int childCount = item.model()->rowCount(item); + if (childCount == 0) { + return false; + } + + for (int i = 0; i < childCount; ++i) { + if (filterAcceptsRowItself(i, item)) { + return true; + } + + if (hasAcceptedChildren(i, item)) { + return true; + } + } + + return false; +} diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index 92cb4af3f..fda1609a7 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -2,7 +2,8 @@ ****************************************************************************** * * @file uavobjectbrowserwidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup UAVObjectBrowserPlugin UAVObject Browser Plugin @@ -30,6 +31,8 @@ #include #include +#include +#include #include "objectpersistence.h" #include "uavobjecttreemodel.h" @@ -38,6 +41,16 @@ class ObjectTreeItem; class Ui_UAVObjectBrowser; class Ui_viewoptions; +class TreeSortFilterProxyModel : public QSortFilterProxyModel { +public: + TreeSortFilterProxyModel(QObject *parent); + +protected: + bool filterAcceptsRow(int source_row, const QModelIndex &source_parent) const; + bool filterAcceptsRowItself(int source_row, const QModelIndex &source_parent) const; + bool hasAcceptedChildren(int source_row, const QModelIndex &source_parent) const; +}; + class UAVObjectBrowserWidget : public QWidget { Q_OBJECT @@ -87,6 +100,8 @@ private slots: void currentChanged(const QModelIndex ¤t, const QModelIndex &previous); void viewSlot(); void viewOptionsChangedSlot(); + void searchLineChanged(QString searchText); + void searchTextCleared(); void splitterMoved(); QString createObjectDescription(UAVObject *object); signals: @@ -99,6 +114,7 @@ private: Ui_viewoptions *m_viewoptions; QDialog *m_viewoptionsDialog; UAVObjectTreeModel *m_model; + TreeSortFilterProxyModel *m_modelProxy; int m_recentlyUpdatedTimeout; QColor m_unknownObjectColor; @@ -110,6 +126,7 @@ private: void updateObjectPersistance(ObjectPersistence::OperationOptions op, UAVObject *obj); void enableSendRequest(bool enable); void updateDescription(); + void resetProxyModel(UAVObjectTreeModel *currentModel); ObjectTreeItem *findCurrentObjectTreeItem(); QString loadFileIntoString(QString fileName); }; diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h index 48466f4fa..687310f40 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h @@ -30,6 +30,7 @@ #include "treeitem.h" #include +#include #include #include #include @@ -127,5 +128,4 @@ private: // Highlight manager to handle highlighting of tree items. HighLightManager *m_highlightManager; }; - #endif // UAVOBJECTTREEMODEL_H From 0f339dfef0a37fabaea2945ef5b9675bdce24d85 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 23 Apr 2016 17:59:24 +0200 Subject: [PATCH 23/58] LP-286 make uavobject model data() method return the TreeItem when called with Qt::UserRole also cleaned up data() method (use switch instead of if mumble jumble) --- .../uavobjectbrowser/uavobjecttreemodel.cpp | 70 ++++++++++--------- 1 file changed, 38 insertions(+), 32 deletions(-) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp index 1e2b7c072..f112cc83d 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp @@ -363,50 +363,56 @@ QVariant UAVObjectTreeModel::data(const QModelIndex &index, int role) const TreeItem *item = static_cast(index.internalPointer()); - if (index.column() == TreeItem::DATA_COLUMN && role == Qt::EditRole) { + switch (role) { + case Qt::DisplayRole: + if (index.column() == TreeItem::DATA_COLUMN) { + EnumFieldTreeItem *fieldItem = dynamic_cast(item); + if (fieldItem) { + int enumIndex = fieldItem->data(index.column()).toInt(); + return fieldItem->enumOptions(enumIndex); + } + } return item->data(index.column()); - } - if (role == Qt::ToolTipRole) { + case Qt::EditRole: + if (index.column() == TreeItem::DATA_COLUMN) { + return item->data(index.column()); + } + return QVariant(); + + case Qt::ToolTipRole: return item->description(); - } - if (role == Qt::ForegroundRole) { + case Qt::ForegroundRole: if (!dynamic_cast(item) && !item->isKnown()) { - return QVariant(m_unknownObjectColor); + return m_unknownObjectColor; } - } + return QVariant(); - if (index.column() == 0 && role == Qt::BackgroundRole) { - if (!dynamic_cast(item) && item->highlighted()) { - return QVariant(m_recentlyUpdatedColor); + case Qt::BackgroundRole: + if (index.column() == TreeItem::TITLE_COLUMN) { + if (!dynamic_cast(item) && item->highlighted()) { + return m_recentlyUpdatedColor; + } + } else if (index.column() == TreeItem::DATA_COLUMN) { + FieldTreeItem *fieldItem = dynamic_cast(item); + if (fieldItem && fieldItem->highlighted()) { + return m_recentlyUpdatedColor; + } + if (fieldItem && fieldItem->changed()) { + return m_manuallyChangedColor; + } } - } + return QVariant(); - if (index.column() == TreeItem::DATA_COLUMN && role == Qt::BackgroundRole) { - FieldTreeItem *fieldItem = dynamic_cast(item); - if (fieldItem && fieldItem->highlighted()) { - return QVariant(m_recentlyUpdatedColor); - } + case Qt::UserRole: + // UserRole gives access to TreeItem + // cast to void* is necessary + return qVariantFromValue((void *)item); - if (fieldItem && fieldItem->changed()) { - return QVariant(m_manuallyChangedColor); - } - } - - if (role != Qt::DisplayRole) { + default: return QVariant(); } - - if (index.column() == TreeItem::DATA_COLUMN) { - EnumFieldTreeItem *fieldItem = dynamic_cast(item); - if (fieldItem) { - int enumIndex = fieldItem->data(index.column()).toInt(); - return fieldItem->enumOptions(enumIndex); - } - } - - return item->data(index.column()); } bool UAVObjectTreeModel::setData(const QModelIndex &index, const QVariant & value, int role) From 8db244b30ade9e8d0672d4d1ef89abac7e65e0d5 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 23 Apr 2016 18:06:41 +0200 Subject: [PATCH 24/58] LP-286 get TreeItem using data() method instead of internalPointer() method not only it is not legal to use internalPointer() outside of the model class but it also requires to do nasty index juggling when using a proxy model --- .../uavobjectbrowser/browseritemdelegate.cpp | 34 +++++++------------ .../uavobjectbrowser/browseritemdelegate.h | 12 +------ .../uavobjectbrowserwidget.cpp | 15 ++++---- 3 files changed, 20 insertions(+), 41 deletions(-) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp index 6fddafa1d..d7b1031db 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp @@ -30,53 +30,45 @@ #include "browseritemdelegate.h" #include "fieldtreeitem.h" -BrowserItemDelegate::BrowserItemDelegate(TreeSortFilterProxyModel *proxyModel, QObject *parent) : +BrowserItemDelegate::BrowserItemDelegate(QObject *parent) : QStyledItemDelegate(parent) -{ - this->proxyModel = proxyModel; -} +{} QWidget *BrowserItemDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem & option, - const QModelIndex & proxyIndex) const + const QModelIndex & index) const { Q_UNUSED(option) - QModelIndex index = proxyModel->mapToSource(proxyIndex); - - FieldTreeItem *item = static_cast(index.internalPointer()); - QWidget *editor = item->createEditor(parent); + FieldTreeItem * item = static_cast(index.data(Qt::UserRole).value()); + QWidget *editor = item->createEditor(parent); Q_ASSERT(editor); return editor; } - void BrowserItemDelegate::setEditorData(QWidget *editor, - const QModelIndex & proxyIndex) const + const QModelIndex & index) const { - QModelIndex index = proxyModel->mapToSource(proxyIndex); - - FieldTreeItem *item = static_cast(index.internalPointer()); - QVariant value = proxyIndex.model()->data(proxyIndex, Qt::EditRole); + FieldTreeItem *item = static_cast(index.data(Qt::UserRole).value()); + QVariant value = index.model()->data(index, Qt::EditRole); item->setEditorValue(editor, value); } void BrowserItemDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, - const QModelIndex &proxyIndex) const + const QModelIndex &index) const { - QModelIndex index = proxyModel->mapToSource(proxyIndex); - - FieldTreeItem *item = static_cast(index.internalPointer()); + FieldTreeItem *item = static_cast(index.data(Qt::UserRole).value()); QVariant value = item->getEditorValue(editor); - bool ret = model->setData(proxyIndex, value, Qt::EditRole); + bool ret = model->setData(index, value, Qt::EditRole); Q_ASSERT(ret); } void BrowserItemDelegate::updateEditorGeometry(QWidget *editor, - const QStyleOptionViewItem &option, const QModelIndex & /* index */) const + const QStyleOptionViewItem &option, const QModelIndex &index) const { + Q_UNUSED(index); editor->setGeometry(option.rect); } diff --git a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h index 2605db7dc..b9d12af04 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.h @@ -31,12 +31,10 @@ #include -class TreeSortFilterProxyModel; - class BrowserItemDelegate : public QStyledItemDelegate { Q_OBJECT public: - explicit BrowserItemDelegate(TreeSortFilterProxyModel *proxyModel, QObject *parent = 0); + explicit BrowserItemDelegate(QObject *parent = 0); QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const; @@ -49,14 +47,6 @@ public: const QStyleOptionViewItem &option, const QModelIndex &index) const; QSize sizeHint(const QStyleOptionViewItem & option, const QModelIndex &index) const; - - -signals: - -public slots: - -private: - TreeSortFilterProxyModel *proxyModel; }; #endif // BROWSERITEMDELEGATE_H diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index 59efba6e1..1e3628649 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -56,8 +56,7 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent m_browser->treeView->setModel(m_modelProxy); m_browser->treeView->setColumnWidth(0, 300); - BrowserItemDelegate *m_delegate = new BrowserItemDelegate(m_modelProxy); - m_browser->treeView->setItemDelegate(m_delegate); + m_browser->treeView->setItemDelegate(new BrowserItemDelegate()); m_browser->treeView->setEditTriggers(QAbstractItemView::AllEditTriggers); m_browser->treeView->setSelectionBehavior(QAbstractItemView::SelectItems); m_mustacheTemplate = loadFileIntoString(QString(":/uavobjectbrowser/resources/uavodescription.mustache")); @@ -191,8 +190,8 @@ void UAVObjectBrowserWidget::requestUpdate() ObjectTreeItem *UAVObjectBrowserWidget::findCurrentObjectTreeItem() { - QModelIndex current = m_modelProxy->mapToSource(m_browser->treeView->currentIndex()); - TreeItem *item = static_cast(current.internalPointer()); + QModelIndex current = m_browser->treeView->currentIndex(); + TreeItem *item = static_cast(current.data(Qt::UserRole).value()); ObjectTreeItem *objItem = 0; while (item) { @@ -277,11 +276,9 @@ void UAVObjectBrowserWidget::currentChanged(const QModelIndex ¤t, const QM { Q_UNUSED(previous); - QModelIndex cindex = m_modelProxy->mapToSource(current); - - TreeItem *item = static_cast(cindex.internalPointer()); - bool enable = true; - if (cindex == QModelIndex()) { + TreeItem *item = static_cast(current.data(Qt::UserRole).value()); + bool enable = true; + if (!current.isValid()) { enable = false; } TopTreeItem *top = dynamic_cast(item); From fa0686eba1a8020b86d8a0c2e2e6b4516c8e38af Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 23 Apr 2016 18:22:43 +0200 Subject: [PATCH 25/58] LP-286 change proxy model source instead of recreating it this also fixes a leak of the previous proxy model --- .../uavobjectbrowserwidget.cpp | 65 ++++++++----------- .../uavobjectbrowser/uavobjectbrowserwidget.h | 1 - .../uavobjectbrowser/uavobjecttreemodel.cpp | 7 +- 3 files changed, 32 insertions(+), 41 deletions(-) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index 1e3628649..fdc598ae0 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -102,22 +102,6 @@ void UAVObjectBrowserWidget::setSplitterState(QByteArray state) m_browser->splitter->restoreState(state); } - -void UAVObjectBrowserWidget::resetProxyModel(UAVObjectTreeModel *currentModel) -{ - m_modelProxy = new TreeSortFilterProxyModel(this); - m_modelProxy->setSourceModel(currentModel); - m_modelProxy->setDynamicSortFilter(true); - m_browser->treeView->setModel(m_modelProxy); - - BrowserItemDelegate *m_delegate = new BrowserItemDelegate(m_modelProxy); - m_browser->treeView->setItemDelegate(m_delegate); - - if (!m_browser->searchLine->text().isEmpty()) { - emit searchLineChanged(m_browser->searchLine->text()); - } -} - void UAVObjectBrowserWidget::showMetaData(bool show) { QList metaIndexes = m_model->getMetaDataIndexes(); @@ -135,34 +119,42 @@ void UAVObjectBrowserWidget::showDescription(bool show) void UAVObjectBrowserWidget::categorize(bool categorize) { + UAVObjectTreeModel *model = new UAVObjectTreeModel(0, categorize, m_viewoptions->cbScientific->isChecked()); + + model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); + model->setManuallyChangedColor(m_manuallyChangedColor); + model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); + model->setOnlyHilightChangedValues(m_onlyHilightChangedValues); + model->setUnknowObjectColor(m_unknownObjectColor); + UAVObjectTreeModel *tmpModel = m_model; - - m_model = new UAVObjectTreeModel(0, categorize, m_viewoptions->cbScientific->isChecked()); - resetProxyModel(m_model); - m_model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); - m_model->setManuallyChangedColor(m_manuallyChangedColor); - m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); - m_model->setOnlyHilightChangedValues(m_onlyHilightChangedValues); - m_model->setUnknowObjectColor(m_unknownObjectColor); - showMetaData(m_viewoptions->cbMetaData->isChecked()); - connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection); - + m_model = model; + m_modelProxy->setSourceModel(m_model); delete tmpModel; + + showMetaData(m_viewoptions->cbMetaData->isChecked()); + + // FIXME this causes a collapse all if filter is on + searchLineChanged(m_browser->searchLine->text()); } void UAVObjectBrowserWidget::useScientificNotation(bool scientific) { + UAVObjectTreeModel *model = new UAVObjectTreeModel(0, m_viewoptions->cbCategorized->isChecked(), scientific); + + model->setManuallyChangedColor(m_manuallyChangedColor); + model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); + model->setUnknowObjectColor(m_unknownObjectColor); + UAVObjectTreeModel *tmpModel = m_model; - - m_model = new UAVObjectTreeModel(0, m_viewoptions->cbCategorized->isChecked(), scientific); - resetProxyModel(m_model); - m_model->setManuallyChangedColor(m_manuallyChangedColor); - m_model->setRecentlyUpdatedTimeout(m_recentlyUpdatedTimeout); - m_model->setUnknowObjectColor(m_unknownObjectColor); - showMetaData(m_viewoptions->cbMetaData->isChecked()); - connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection); - + m_model = model; + m_modelProxy->setSourceModel(m_model); delete tmpModel; + + showMetaData(m_viewoptions->cbMetaData->isChecked()); + + // FIXME this causes a collapse all if filter is on + searchLineChanged(m_browser->searchLine->text()); } void UAVObjectBrowserWidget::sendUpdate() @@ -424,7 +416,6 @@ void UAVObjectBrowserWidget::updateDescription() void UAVObjectBrowserWidget::searchLineChanged(QString searchText) { m_modelProxy->setFilterRegExp(QRegExp(searchText, Qt::CaseInsensitive, QRegExp::FixedString)); - showMetaData(m_viewoptions->cbMetaData->isChecked()); if (!searchText.isEmpty()) { m_browser->treeView->expandAll(); } else { diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index fda1609a7..7c4c3eaf0 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -126,7 +126,6 @@ private: void updateObjectPersistance(ObjectPersistence::OperationOptions op, UAVObject *obj); void enableSendRequest(bool enable); void updateDescription(); - void resetProxyModel(UAVObjectTreeModel *currentModel); ObjectTreeItem *findCurrentObjectTreeItem(); QString loadFileIntoString(QString fileName); }; diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp index f112cc83d..a22fcf1c9 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp @@ -306,10 +306,11 @@ QModelIndex UAVObjectTreeModel::parent(const QModelIndex &index) const return QModelIndex(); } - TreeItem *childItem = static_cast(index.internalPointer()); - TreeItem *parentItem = childItem->parent(); + TreeItem *item = static_cast(index.internalPointer()); - if (parentItem == m_rootItem) { + TreeItem *parentItem = item->parent(); + if (!parentItem) { + // item is root has no parent... return QModelIndex(); } From 6328b8a593ccb24ed68716c96adb9984250897da Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 23 Apr 2016 18:32:32 +0200 Subject: [PATCH 26/58] LP-286 minor code cleanups remove unused class members reorganize some methods --- .../uavobjectbrowserwidget.cpp | 40 ++++++++++++------- .../uavobjectbrowser/uavobjectbrowserwidget.h | 11 +++-- .../uavobjectbrowser/uavobjecttreemodel.cpp | 26 ++++++------ .../uavobjectbrowser/uavobjecttreemodel.h | 1 + 4 files changed, 48 insertions(+), 30 deletions(-) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index fdc598ae0..9d13b2c40 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -44,43 +44,54 @@ UAVObjectBrowserWidget::UAVObjectBrowserWidget(QWidget *parent) : QWidget(parent) { - m_browser = new Ui_UAVObjectBrowser(); - m_viewoptions = new Ui_viewoptions(); m_viewoptionsDialog = new QDialog(this); + + m_viewoptions = new Ui_viewoptions(); m_viewoptions->setupUi(m_viewoptionsDialog); - m_browser->setupUi(this); - m_model = new UAVObjectTreeModel(); + + m_model = new UAVObjectTreeModel(this); + m_modelProxy = new TreeSortFilterProxyModel(this); m_modelProxy->setSourceModel(m_model); m_modelProxy->setDynamicSortFilter(true); + + m_browser = new Ui_UAVObjectBrowser(); + m_browser->setupUi(this); m_browser->treeView->setModel(m_modelProxy); m_browser->treeView->setColumnWidth(0, 300); m_browser->treeView->setItemDelegate(new BrowserItemDelegate()); m_browser->treeView->setEditTriggers(QAbstractItemView::AllEditTriggers); m_browser->treeView->setSelectionBehavior(QAbstractItemView::SelectItems); + m_mustacheTemplate = loadFileIntoString(QString(":/uavobjectbrowser/resources/uavodescription.mustache")); + showMetaData(m_viewoptions->cbMetaData->isChecked()); showDescription(m_viewoptions->cbDescription->isChecked()); + connect(m_browser->treeView->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)), this, SLOT(currentChanged(QModelIndex, QModelIndex)), Qt::UniqueConnection); - connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool))); - connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(categorize(bool))); - connect(m_viewoptions->cbDescription, SIGNAL(toggled(bool)), this, SLOT(showDescription(bool))); connect(m_browser->saveSDButton, SIGNAL(clicked()), this, SLOT(saveObject())); connect(m_browser->readSDButton, SIGNAL(clicked()), this, SLOT(loadObject())); - connect(m_browser->eraseSDButton, SIGNAL(clicked()), this, SLOT(eraseObject())); connect(m_browser->sendButton, SIGNAL(clicked()), this, SLOT(sendUpdate())); connect(m_browser->requestButton, SIGNAL(clicked()), this, SLOT(requestUpdate())); + connect(m_browser->eraseSDButton, SIGNAL(clicked()), this, SLOT(eraseObject())); connect(m_browser->tbView, SIGNAL(clicked()), this, SLOT(viewSlot())); + connect(m_browser->splitter, SIGNAL(splitterMoved(int, int)), this, SLOT(splitterMoved())); + + connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(showMetaData(bool))); + connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); + connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(categorize(bool))); + connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); + connect(m_viewoptions->cbDescription, SIGNAL(toggled(bool)), this, SLOT(showDescription(bool))); + connect(m_viewoptions->cbDescription, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(useScientificNotation(bool))); connect(m_viewoptions->cbScientific, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); - connect(m_viewoptions->cbMetaData, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); - connect(m_viewoptions->cbCategorized, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); - connect(m_viewoptions->cbDescription, SIGNAL(toggled(bool)), this, SLOT(viewOptionsChangedSlot())); - connect(m_browser->splitter, SIGNAL(splitterMoved(int, int)), this, SLOT(splitterMoved())); + + // search field and button connect(m_browser->searchLine, SIGNAL(textChanged(QString)), this, SLOT(searchLineChanged(QString))); connect(m_browser->searchClearButton, SIGNAL(clicked(bool)), this, SLOT(searchTextCleared())); + enableSendRequest(false); } @@ -106,9 +117,9 @@ void UAVObjectBrowserWidget::showMetaData(bool show) { QList metaIndexes = m_model->getMetaDataIndexes(); foreach(QModelIndex modelIndex, metaIndexes) { - QModelIndex proxyModelindex = m_modelProxy->mapFromSource(modelIndex); + QModelIndex proxyModelIndex = m_modelProxy->mapFromSource(modelIndex); - m_browser->treeView->setRowHidden(proxyModelindex.row(), proxyModelindex.parent(), !show); + m_browser->treeView->setRowHidden(proxyModelIndex.row(), proxyModelIndex.parent(), !show); } } @@ -140,6 +151,7 @@ void UAVObjectBrowserWidget::categorize(bool categorize) void UAVObjectBrowserWidget::useScientificNotation(bool scientific) { + // TODO we should have the model update itself instead of rebuilding it UAVObjectTreeModel *model = new UAVObjectTreeModel(0, m_viewoptions->cbCategorized->isChecked(), scientific); model->setManuallyChangedColor(m_manuallyChangedColor); diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index 7c4c3eaf0..c0051ad67 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -29,12 +29,14 @@ #ifndef UAVOBJECTBROWSERWIDGET_H_ #define UAVOBJECTBROWSERWIDGET_H_ +#include "uavobjecttreemodel.h" + +#include "objectpersistence.h" + #include #include #include #include -#include "objectpersistence.h" -#include "uavobjecttreemodel.h" class QPushButton; class ObjectTreeItem; @@ -85,6 +87,7 @@ public: } void setViewOptions(bool categorized, bool scientific, bool metadata, bool description); void setSplitterState(QByteArray state); + public slots: void showMetaData(bool show); void showDescription(bool show); @@ -104,12 +107,12 @@ private slots: void searchTextCleared(); void splitterMoved(); QString createObjectDescription(UAVObject *object); + signals: void viewOptionsChanged(bool categorized, bool scientific, bool metadata, bool description); void splitterChanged(QByteArray state); + private: - QPushButton *m_requestUpdate; - QPushButton *m_sendUpdate; Ui_UAVObjectBrowser *m_browser; Ui_viewoptions *m_viewoptions; QDialog *m_viewoptionsDialog; diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp index a22fcf1c9..7c9f5b185 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp @@ -68,20 +68,23 @@ UAVObjectTreeModel::~UAVObjectTreeModel() void UAVObjectTreeModel::setupModelData(UAVObjectManager *objManager) { + m_settingsTree = new TopTreeItem(tr("Settings")); + m_settingsTree->setHighlightManager(m_highlightManager); + connect(m_settingsTree, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *))); + + m_nonSettingsTree = new TopTreeItem(tr("Data Objects")); + m_nonSettingsTree->setHighlightManager(m_highlightManager); + connect(m_nonSettingsTree, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *))); + // root QList rootData; rootData << tr("Property") << tr("Value") << tr("Unit"); - m_rootItem = new TreeItem(rootData); - - m_settingsTree = new TopTreeItem(tr("Settings"), m_rootItem); - m_settingsTree->setHighlightManager(m_highlightManager); - m_rootItem->appendChild(m_settingsTree); - m_nonSettingsTree = new TopTreeItem(tr("Data Objects"), m_rootItem); - m_nonSettingsTree->setHighlightManager(m_highlightManager); - m_rootItem->appendChild(m_nonSettingsTree); + m_rootItem = new TreeItem(rootData); m_rootItem->setHighlightManager(m_highlightManager); - connect(m_settingsTree, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *))); - connect(m_nonSettingsTree, SIGNAL(updateHighlight(TreeItem *)), this, SLOT(updateHighlight(TreeItem *))); + + // tree item takes ownership of its children + m_rootItem->appendChild(m_settingsTree); + m_rootItem->appendChild(m_nonSettingsTree); QList< QList > objList = objManager->getDataObjects(); foreach(QList list, objList) { @@ -258,8 +261,7 @@ void UAVObjectTreeModel::addSingleField(int index, UAVObjectField *field, TreeIt parent->appendChild(item); } -QModelIndex UAVObjectTreeModel::index(int row, int column, const QModelIndex &parent) -const +QModelIndex UAVObjectTreeModel::index(int row, int column, const QModelIndex &parent) const { if (!hasIndex(row, column, parent)) { return QModelIndex(); diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h index 687310f40..6025679c3 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h @@ -128,4 +128,5 @@ private: // Highlight manager to handle highlighting of tree items. HighLightManager *m_highlightManager; }; + #endif // UAVOBJECTTREEMODEL_H From 947dbf88abb7e9bdd377e1da13810a69f4c05cec Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 23 Apr 2016 18:34:20 +0200 Subject: [PATCH 27/58] LP-286 rephrase filter placeholder text --- ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui index 5feed5889..54a937b6f 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowser.ui @@ -223,7 +223,7 @@ - Search for UAVObject... + type filter text From 29b33453f36a6a362948c52f6a9cfb634f0e2f23 Mon Sep 17 00:00:00 2001 From: Philippe Renon Date: Sat, 23 Apr 2016 18:35:18 +0200 Subject: [PATCH 28/58] LP-286 minor optimization: replace map contains+get with get --- .../src/plugins/uavobjectbrowser/treeitem.h | 4 ++-- .../uavobjectbrowserwidget.cpp | 24 +++++++++++++++---- 2 files changed, 21 insertions(+), 7 deletions(-) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/treeitem.h b/ground/gcs/src/plugins/uavobjectbrowser/treeitem.h index bd8504870..253ec041c 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/treeitem.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/treeitem.h @@ -259,7 +259,7 @@ public: DataObjectTreeItem *findDataObjectTreeItemByObjectId(quint32 objectId) { - return m_objectTreeItemsPerObjectIds.contains(objectId) ? m_objectTreeItemsPerObjectIds[objectId] : 0; + return m_objectTreeItemsPerObjectIds.value(objectId, 0); } void addMetaObjectTreeItem(quint32 objectId, MetaObjectTreeItem *oti) @@ -269,7 +269,7 @@ public: MetaObjectTreeItem *findMetaObjectTreeItemByObjectId(quint32 objectId) { - return m_metaObjectTreeItemsPerObjectIds.contains(objectId) ? m_metaObjectTreeItemsPerObjectIds[objectId] : 0; + return m_metaObjectTreeItemsPerObjectIds.value(objectId, 0); } QList getMetaObjectItems(); diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index 9d13b2c40..beb314263 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -115,6 +115,7 @@ void UAVObjectBrowserWidget::setSplitterState(QByteArray state) void UAVObjectBrowserWidget::showMetaData(bool show) { + // TODO update the model directly instead of hiding rows... QList metaIndexes = m_model->getMetaDataIndexes(); foreach(QModelIndex modelIndex, metaIndexes) { QModelIndex proxyModelIndex = m_modelProxy->mapFromSource(modelIndex); @@ -130,6 +131,8 @@ void UAVObjectBrowserWidget::showDescription(bool show) void UAVObjectBrowserWidget::categorize(bool categorize) { + // TODO we should update the model instead of rebuilding it + // a side effect of rebuilding is that some state is lost (expand state, ...) UAVObjectTreeModel *model = new UAVObjectTreeModel(0, categorize, m_viewoptions->cbScientific->isChecked()); model->setRecentlyUpdatedColor(m_recentlyUpdatedColor); @@ -145,13 +148,16 @@ void UAVObjectBrowserWidget::categorize(bool categorize) showMetaData(m_viewoptions->cbMetaData->isChecked()); - // FIXME this causes a collapse all if filter is on - searchLineChanged(m_browser->searchLine->text()); + // force an expand all if search text is not empty + if (!m_browser->searchLine->text().isEmpty()) { + searchLineChanged(m_browser->searchLine->text()); + } } void UAVObjectBrowserWidget::useScientificNotation(bool scientific) { - // TODO we should have the model update itself instead of rebuilding it + // TODO we should update the model instead of rebuilding it + // a side effect of rebuilding is that some state is lost (expand state, ...) UAVObjectTreeModel *model = new UAVObjectTreeModel(0, m_viewoptions->cbCategorized->isChecked(), scientific); model->setManuallyChangedColor(m_manuallyChangedColor); @@ -165,14 +171,19 @@ void UAVObjectBrowserWidget::useScientificNotation(bool scientific) showMetaData(m_viewoptions->cbMetaData->isChecked()); - // FIXME this causes a collapse all if filter is on - searchLineChanged(m_browser->searchLine->text()); + // force an expand all if search text is not empty + if (!m_browser->searchLine->text().isEmpty()) { + searchLineChanged(m_browser->searchLine->text()); + } } void UAVObjectBrowserWidget::sendUpdate() { + // TODO why steal focys ? this->setFocus(); + ObjectTreeItem *objItem = findCurrentObjectTreeItem(); + if (objItem != NULL) { objItem->apply(); UAVObject *obj = objItem->object(); @@ -221,12 +232,15 @@ QString UAVObjectBrowserWidget::loadFileIntoString(QString fileName) void UAVObjectBrowserWidget::saveObject() { + // TODO why steal focys ? this->setFocus(); + // Send update so that the latest value is saved sendUpdate(); // Save object ObjectTreeItem *objItem = findCurrentObjectTreeItem(); + if (objItem != NULL) { UAVObject *obj = objItem->object(); Q_ASSERT(obj); From f0b3156abe63027ecb1d57c9d27190e0d206226e Mon Sep 17 00:00:00 2001 From: Mateusz Kaduk Date: Sat, 23 Apr 2016 23:06:08 +0200 Subject: [PATCH 29/58] LP-286 TauLabs acknowledgements for parts of the code --- .../gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp | 1 + ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h | 1 + 2 files changed, 2 insertions(+) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index beb314263..5be97bbe6 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -3,6 +3,7 @@ * * @file uavobjectbrowserwidget.cpp * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * Tau Labs, http://taulabs.org, Copyright (C) 2013 * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h index c0051ad67..905d9e206 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.h @@ -3,6 +3,7 @@ * * @file uavobjectbrowserwidget.h * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * Tau Labs, http://taulabs.org, Copyright (C) 2013 * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ From 1f0bf155ce8c2b3e1f7983d4ae85a5e5cd5687ce Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Sun, 24 Apr 2016 02:03:50 +0200 Subject: [PATCH 30/58] LP-293 make use of NELEMENTS() macro instead of defining own version NELEM() --- flight/libraries/alarms.c | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index 772af3da0..506efc865 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -38,8 +38,6 @@ #define PIOS_ALARM_GRACETIME 1000 #endif // PIOS_ALARM_GRACETIME -#define NELEM(x) ((sizeof(x) / sizeof((x)[0]))) - // Private types // Private variables @@ -328,7 +326,7 @@ size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, Sy { size_t pos = 0; - PIOS_STATIC_ASSERT(NELEM(systemalarms_alarm_names) == SYSTEMALARMS_ALARM_NUMELEM); + PIOS_STATIC_ASSERT(NELEMENTS(systemalarms_alarm_names) == SYSTEMALARMS_ALARM_NUMELEM); for (unsigned severity = SYSTEMALARMS_ALARM_ERROR; severity >= level; --severity) { // should we prepend severity level here? No, not for now. @@ -349,13 +347,13 @@ size_t AlarmString(SystemAlarmsData *alarm, char *buffer, size_t buffer_size, Sy switch (i) { case SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION: - if (alarm->ExtendedAlarmStatus.SystemConfiguration < NELEM(systemalarms_extendedalarmstatus_names)) { + if (alarm->ExtendedAlarmStatus.SystemConfiguration < NELEMENTS(systemalarms_extendedalarmstatus_names)) { current_msg = systemalarms_extendedalarmstatus_names[alarm->ExtendedAlarmStatus.SystemConfiguration]; } break; case SYSTEMALARMS_ALARM_BOOTFAULT: - if (alarm->ExtendedAlarmStatus.BootFault < NELEM(systemalarms_extendedalarmstatus_names)) { + if (alarm->ExtendedAlarmStatus.BootFault < NELEMENTS(systemalarms_extendedalarmstatus_names)) { current_msg = systemalarms_extendedalarmstatus_names[alarm->ExtendedAlarmStatus.BootFault]; } break; From 1c67853bfde7aeda68800d966fc35625d04e97c7 Mon Sep 17 00:00:00 2001 From: Mateusz Kaduk Date: Sun, 24 Apr 2016 09:13:01 +0200 Subject: [PATCH 31/58] LP-286 Clean-up spelling, headers and uncrustify --- .../src/plugins/uavobjectbrowser/browseritemdelegate.cpp | 7 +++---- .../plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp | 4 ++-- .../gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h | 1 - 3 files changed, 5 insertions(+), 7 deletions(-) diff --git a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp index d7b1031db..017dd8b40 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/browseritemdelegate.cpp @@ -26,17 +26,16 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "uavobjectbrowserwidget.h" #include "browseritemdelegate.h" #include "fieldtreeitem.h" -BrowserItemDelegate::BrowserItemDelegate(QObject *parent) : +BrowserItemDelegate::BrowserItemDelegate(QObject *parent) : QStyledItemDelegate(parent) {} QWidget *BrowserItemDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem & option, - const QModelIndex & index) const + const QModelIndex &index) const { Q_UNUSED(option) FieldTreeItem * item = static_cast(index.data(Qt::UserRole).value()); @@ -46,7 +45,7 @@ QWidget *BrowserItemDelegate::createEditor(QWidget *parent, } void BrowserItemDelegate::setEditorData(QWidget *editor, - const QModelIndex & index) const + const QModelIndex &index) const { FieldTreeItem *item = static_cast(index.data(Qt::UserRole).value()); QVariant value = index.model()->data(index, Qt::EditRole); diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index 5be97bbe6..b271809b8 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -180,7 +180,7 @@ void UAVObjectBrowserWidget::useScientificNotation(bool scientific) void UAVObjectBrowserWidget::sendUpdate() { - // TODO why steal focys ? + // TODO why steal focus ? this->setFocus(); ObjectTreeItem *objItem = findCurrentObjectTreeItem(); @@ -233,7 +233,7 @@ QString UAVObjectBrowserWidget::loadFileIntoString(QString fileName) void UAVObjectBrowserWidget::saveObject() { - // TODO why steal focys ? + // TODO why steal focus ? this->setFocus(); // Send update so that the latest value is saved diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h index 6025679c3..48466f4fa 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.h @@ -30,7 +30,6 @@ #include "treeitem.h" #include -#include #include #include #include From 47d2746fba4da410466de9e5d364b73f7c5f49ea Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Mon, 25 Apr 2016 17:37:06 +0200 Subject: [PATCH 32/58] LP-295: uncrustify --- flight/libraries/plans.c | 1 + flight/modules/PathFollower/vtolautotakeoffcontroller.cpp | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/libraries/plans.c b/flight/libraries/plans.c index 0e32c2ec7..42e9945aa 100644 --- a/flight/libraries/plans.c +++ b/flight/libraries/plans.c @@ -174,6 +174,7 @@ void plan_setup_returnToBase() void plan_setup_AutoTakeoff() { PathDesiredData pathDesired; + memset(&pathDesired, 0, sizeof(PathDesiredData)); PositionStateData positionState; diff --git a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp index 5087adaff..444535194 100644 --- a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp @@ -369,7 +369,6 @@ void VtolAutoTakeoffController::UpdateAutoPilot() } } break; - case STATUSVTOLAUTOTAKEOFF_CONTROLSTATE_ABORT: { FlightStatusData flightStatus; From 37d96759246d1ce1e2cfc86dcc7021cd5deb8445 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Mon, 25 Apr 2016 18:05:15 +0200 Subject: [PATCH 33/58] LP-295 fixed uavobject definitions as per pull request comment --- .../fixedwingpathfollowersettings.xml | 76 ++++++------------- .../flightmodesettings.xml | 2 +- 2 files changed, 26 insertions(+), 52 deletions(-) diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml index 68b0a406e..4e880a11f 100644 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml +++ b/shared/uavobjectdefinition/fixedwingpathfollowersettings.xml @@ -3,69 +3,43 @@ Settings for the @ref FixedWingPathFollowerModule - - - - - - + + + - - - - + + - - - - + + - - + - - + - - - - - - - - + + + + - - - - - - - - + + + + - + elementnames="RollDeg,PitchDeg,YawDeg,MaxDecelerationDeltaMPS" defaultvalue="25.0,25.0,25.0,4.0" + description="maximum margins from attempted attitude allowed during takeoff -- In flight Roll/Pitch are added to RollLimit/PitchLimit as max limits - throttle is cut when beyond if roll > RollLimit.Max + TakeOffLimits.RollDeg the same happens when MaxDecelerationDeltaMPS below Lowspeed limit if speed < Safetymargins.Lowspeed*HorizontalVelMin - TakeOffLimits.MaxDecelerationDeltaMPS" /> - - + + - + diff --git a/shared/uavobjectdefinition/flightmodesettings.xml b/shared/uavobjectdefinition/flightmodesettings.xml index 4fb324883..71f2b6453 100644 --- a/shared/uavobjectdefinition/flightmodesettings.xml +++ b/shared/uavobjectdefinition/flightmodesettings.xml @@ -94,7 +94,7 @@ - + From bf80ede40119b5312f099a54e2499135b8304c15 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Mon, 25 Apr 2016 18:12:31 +0200 Subject: [PATCH 34/58] LP-295: fixed comments and formatting --- flight/modules/PathFollower/fixedwinglandcontroller.cpp | 2 +- flight/modules/PathFollower/inc/vtolautotakeofffsm.h | 2 +- flight/modules/PathFollower/vtolautotakeoffcontroller.cpp | 6 ++++-- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/flight/modules/PathFollower/fixedwinglandcontroller.cpp b/flight/modules/PathFollower/fixedwinglandcontroller.cpp index d11d4c4fe..cabc21060 100644 --- a/flight/modules/PathFollower/fixedwinglandcontroller.cpp +++ b/flight/modules/PathFollower/fixedwinglandcontroller.cpp @@ -98,7 +98,7 @@ int32_t FixedWingLandController::Initialize(FixedWingPathFollowerSettingsData *p } /** - * reset integrals + * reset globals, (integrals, accumulated errors and timers) */ void FixedWingLandController::resetGlobals() { diff --git a/flight/modules/PathFollower/inc/vtolautotakeofffsm.h b/flight/modules/PathFollower/inc/vtolautotakeofffsm.h index f683ee33c..0ac6b919d 100644 --- a/flight/modules/PathFollower/inc/vtolautotakeofffsm.h +++ b/flight/modules/PathFollower/inc/vtolautotakeofffsm.h @@ -47,7 +47,7 @@ typedef enum { AUTOTAKEOFF_STATE_THRUSTDOWN, // Thrust down sequence AUTOTAKEOFF_STATE_THRUSTOFF, // Thrust is now off AUTOTAKEOFF_STATE_DISARMED, // Disarmed - AUTOTAKEOFF_STATE_ABORT, // Abort on error triggerig fallback to land + AUTOTAKEOFF_STATE_ABORT, // Abort on error triggers fallback to land AUTOTAKEOFF_STATE_SIZE } PathFollowerFSM_AutoTakeoffState_T; diff --git a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp index 444535194..6fa6c8620 100644 --- a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp @@ -130,8 +130,8 @@ uint8_t VtolAutoTakeoffController::Mode(void) void VtolAutoTakeoffController::ObjectiveUpdated(void) { if (mOverride) { - // override pathDesired from PathPLanner with current position, - // as we deliberately don' not care about the location of the waypoints on the map + // override pathDesired from PathPlanner with current position, + // as we deliberately don't care about the location of the waypoints on the map float velocity_down; float autotakeoff_height; PositionStateData positionState; @@ -161,6 +161,8 @@ void VtolAutoTakeoffController::ObjectiveUpdated(void) controlDown.UpdatePositionSetpoint(pathDesired->End.Down); } } + +// Controller deactivated void VtolAutoTakeoffController::Deactivate(void) { if (mActive) { From e1394febb0a946e61d1e9e8bcc65615404394768 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Mon, 25 Apr 2016 18:45:35 +0200 Subject: [PATCH 35/58] LP-295 fixed file headers for all touched files --- flight/libraries/paths.c | 5 ++++- flight/libraries/plans.c | 11 +++++------ flight/modules/ManualControl/pathfollowerhandler.c | 12 +++++------- .../PathFollower/fixedwingautotakeoffcontroller.cpp | 5 ++++- .../modules/PathFollower/fixedwingflycontroller.cpp | 5 ++++- .../modules/PathFollower/fixedwinglandcontroller.cpp | 5 ++++- .../inc/fixedwingautotakeoffcontroller.h | 5 +++-- .../PathFollower/inc/fixedwingflycontroller.h | 5 +++-- .../PathFollower/inc/fixedwinglandcontroller.h | 5 +++-- .../PathFollower/inc/vtolautotakeoffcontroller.h | 5 +++-- flight/modules/PathFollower/inc/vtolautotakeofffsm.h | 5 +++-- flight/modules/PathFollower/inc/vtollandcontroller.h | 5 +++-- flight/modules/PathFollower/pathfollower.cpp | 4 +++- .../PathFollower/vtolautotakeoffcontroller.cpp | 4 +++- flight/modules/PathFollower/vtollandcontroller.cpp | 4 +++- flight/modules/PathPlanner/pathplanner.c | 5 +++-- ground/gcs/src/plugins/hitl/fgsimulator.cpp | 3 ++- 17 files changed, 58 insertions(+), 35 deletions(-) diff --git a/flight/libraries/paths.c b/flight/libraries/paths.c index 620493792..c5d473d06 100644 --- a/flight/libraries/paths.c +++ b/flight/libraries/paths.c @@ -2,11 +2,14 @@ ****************************************************************************** * * @file paths.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * * @brief Library path manipulation * * @see The GNU Public License (GPL) Version 3 * + * @addtogroup LibrePilotLibraries LibrePilot Libraries Navigation *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/flight/libraries/plans.c b/flight/libraries/plans.c index 42e9945aa..9331256c0 100644 --- a/flight/libraries/plans.c +++ b/flight/libraries/plans.c @@ -1,16 +1,15 @@ /** ****************************************************************************** - * @addtogroup OpenPilotLibraries OpenPilot Libraries - * @{ - * @addtogroup Navigation - * @brief setups RTH/PH and other pathfollower/pathplanner status - * @{ * * @file plan.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * + * @brief setups RTH/PH and other pathfollower/pathplanner status * * @see The GNU Public License (GPL) Version 3 * + * @addtogroup LibrePilotLibraries LibrePilot Libraries Navigation ******************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/flight/modules/ManualControl/pathfollowerhandler.c b/flight/modules/ManualControl/pathfollowerhandler.c index 0d5c8078d..a48a754ce 100644 --- a/flight/modules/ManualControl/pathfollowerhandler.c +++ b/flight/modules/ManualControl/pathfollowerhandler.c @@ -1,16 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup ManualControl - * @brief Interpretes the control input in ManualControlCommand - * @{ - * * @file pathfollowerhandler.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * + * @brief Interpretes the control input in ManualControlCommand * * @see The GNU Public License (GPL) Version 3 * + * @addtogroup LibrePilotModules LibrePilot Modules ManualControl ******************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp index 80b72d40d..656a5b631 100644 --- a/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/fixedwingautotakeoffcontroller.cpp @@ -2,10 +2,13 @@ ****************************************************************************** * * @file FixedWingAutoTakeoffController.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Fixed wing fly controller implementation * @see The GNU Public License (GPL) Version 3 * + * @addtogroup LibrePilot LibrePilotModules Modules PathFollower Navigation + * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/flight/modules/PathFollower/fixedwingflycontroller.cpp b/flight/modules/PathFollower/fixedwingflycontroller.cpp index 432b97c4e..1dcbd08d9 100644 --- a/flight/modules/PathFollower/fixedwingflycontroller.cpp +++ b/flight/modules/PathFollower/fixedwingflycontroller.cpp @@ -2,10 +2,13 @@ ****************************************************************************** * * @file FixedWingFlyController.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Fixed wing fly controller implementation * @see The GNU Public License (GPL) Version 3 * + * @addtogroup LibrePilot LibrePilotModules Modules PathFollower Navigation + * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/flight/modules/PathFollower/fixedwinglandcontroller.cpp b/flight/modules/PathFollower/fixedwinglandcontroller.cpp index cabc21060..c4b427c67 100644 --- a/flight/modules/PathFollower/fixedwinglandcontroller.cpp +++ b/flight/modules/PathFollower/fixedwinglandcontroller.cpp @@ -2,10 +2,13 @@ ****************************************************************************** * * @file FixedWingLandController.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Fixed wing fly controller implementation * @see The GNU Public License (GPL) Version 3 * + * @addtogroup LibrePilot LibrePilotModules Modules PathFollower Navigation + * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify diff --git a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h index 6fc06fafe..6930bd7db 100644 --- a/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingautotakeoffcontroller.h @@ -1,13 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup LibrePilotModules LibrePilot Modules * @{ * @addtogroup FixedWing CONTROL interface class * @brief CONTROL interface class for pathfollower fixed wing fly controller * @{ * * @file fixedwingautotakeoffcontroller.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for fixed wing fly objectives * * @see The GNU Public License (GPL) Version 3 diff --git a/flight/modules/PathFollower/inc/fixedwingflycontroller.h b/flight/modules/PathFollower/inc/fixedwingflycontroller.h index a78c7c503..14c5e490c 100644 --- a/flight/modules/PathFollower/inc/fixedwingflycontroller.h +++ b/flight/modules/PathFollower/inc/fixedwingflycontroller.h @@ -1,13 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup LibrePilotModules LibrePilot Modules * @{ * @addtogroup FixedWing CONTROL interface class * @brief CONTROL interface class for pathfollower fixed wing fly controller * @{ * * @file fixedwingflycontroller.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for fixed wing fly objectives * * @see The GNU Public License (GPL) Version 3 diff --git a/flight/modules/PathFollower/inc/fixedwinglandcontroller.h b/flight/modules/PathFollower/inc/fixedwinglandcontroller.h index 9643dea8c..5e0dab889 100644 --- a/flight/modules/PathFollower/inc/fixedwinglandcontroller.h +++ b/flight/modules/PathFollower/inc/fixedwinglandcontroller.h @@ -1,13 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup LibrePilotModules LibrePilot Modules * @{ * @addtogroup FixedWing CONTROL interface class * @brief CONTROL interface class for pathfollower fixed wing fly controller * @{ * * @file fixedwinglandcontroller.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for fixed wing fly objectives * * @see The GNU Public License (GPL) Version 3 diff --git a/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h b/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h index b7d103618..a7617d09c 100644 --- a/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h +++ b/flight/modules/PathFollower/inc/vtolautotakeoffcontroller.h @@ -1,13 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup LibrePilotModules LibrePilot Modules * @{ * @addtogroup PathFollower CONTROL interface class * @brief vtol land controller class * @{ * * @file vtollandcontroller.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for landing sequence * * @see The GNU Public License (GPL) Version 3 diff --git a/flight/modules/PathFollower/inc/vtolautotakeofffsm.h b/flight/modules/PathFollower/inc/vtolautotakeofffsm.h index 0ac6b919d..3f8badb70 100644 --- a/flight/modules/PathFollower/inc/vtolautotakeofffsm.h +++ b/flight/modules/PathFollower/inc/vtolautotakeofffsm.h @@ -1,13 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup LibrePilotModules LibrePilot Modules * @{ * @addtogroup PathFollower FSM * @brief Executes landing sequence via an FSM * @{ * * @file vtollandfsm.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes FSM for landing sequence * * @see The GNU Public License (GPL) Version 3 diff --git a/flight/modules/PathFollower/inc/vtollandcontroller.h b/flight/modules/PathFollower/inc/vtollandcontroller.h index 0c3039629..21712345f 100644 --- a/flight/modules/PathFollower/inc/vtollandcontroller.h +++ b/flight/modules/PathFollower/inc/vtollandcontroller.h @@ -1,13 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup LibrePilotModules LibrePilot Modules * @{ * @addtogroup PathFollower CONTROL interface class * @brief vtol land controller class * @{ * * @file vtollandcontroller.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes CONTROL for landing sequence * * @see The GNU Public License (GPL) Version 3 diff --git a/flight/modules/PathFollower/pathfollower.cpp b/flight/modules/PathFollower/pathfollower.cpp index e73ad8c24..562b2e9b3 100644 --- a/flight/modules/PathFollower/pathfollower.cpp +++ b/flight/modules/PathFollower/pathfollower.cpp @@ -2,12 +2,14 @@ ****************************************************************************** * * @file pathfollower.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief This module compared @ref PositionActuatl to @ref ActiveWaypoint * and sets @ref AttitudeDesired. It only does this when the FlightMode field * of @ref ManualControlCommand is Auto. * * @see The GNU Public License (GPL) Version 3 + * @addtogroup LibrePilot LibrePilotModules Modules PathFollower Navigation * *****************************************************************************/ /* diff --git a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp index 6fa6c8620..0c0bc6490 100644 --- a/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp +++ b/flight/modules/PathFollower/vtolautotakeoffcontroller.cpp @@ -2,9 +2,11 @@ ****************************************************************************** * * @file vtollandcontroller.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Vtol landing controller loop * @see The GNU Public License (GPL) Version 3 + * @addtogroup LibrePilot LibrePilotModules Modules PathFollower Navigation * *****************************************************************************/ /* diff --git a/flight/modules/PathFollower/vtollandcontroller.cpp b/flight/modules/PathFollower/vtollandcontroller.cpp index 07e02e80c..7362526bf 100644 --- a/flight/modules/PathFollower/vtollandcontroller.cpp +++ b/flight/modules/PathFollower/vtollandcontroller.cpp @@ -2,9 +2,11 @@ ****************************************************************************** * * @file vtollandcontroller.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Vtol landing controller loop * @see The GNU Public License (GPL) Version 3 + * @addtogroup LibrePilot LibrePilotModules Modules PathFollower Navigation * *****************************************************************************/ /* diff --git a/flight/modules/PathPlanner/pathplanner.c b/flight/modules/PathPlanner/pathplanner.c index 75bd1336a..cda7bfcf4 100644 --- a/flight/modules/PathPlanner/pathplanner.c +++ b/flight/modules/PathPlanner/pathplanner.c @@ -1,13 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup LibrePilotModules LibrePilot Modules * @{ * @addtogroup PathPlanner Path Planner Module * @brief Executes a series of waypoints * @{ * * @file pathplanner.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @brief Executes a series of waypoints * * @see The GNU Public License (GPL) Version 3 diff --git a/ground/gcs/src/plugins/hitl/fgsimulator.cpp b/ground/gcs/src/plugins/hitl/fgsimulator.cpp index aa0bd4b88..92301da20 100644 --- a/ground/gcs/src/plugins/hitl/fgsimulator.cpp +++ b/ground/gcs/src/plugins/hitl/fgsimulator.cpp @@ -2,7 +2,8 @@ ****************************************************************************** * * @file flightgearbridge.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2015. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup HITLPlugin HITL Plugin From 6f9d96be2ed8ff1c23402468131814272ad34549 Mon Sep 17 00:00:00 2001 From: James Duley Date: Wed, 27 Apr 2016 21:44:11 +0100 Subject: [PATCH 36/58] Update travis to build with osgearth --- .travis.yml | 4 ++-- package/linux/debian/control | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.travis.yml b/.travis.yml index 7e50b0ab6..2ec57c425 100644 --- a/.travis.yml +++ b/.travis.yml @@ -7,9 +7,9 @@ dist: trusty before_install: - sudo add-apt-repository ppa:librepilot/tools -y - sudo apt-get update -q - - sudo apt-get install -y libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools + - sudo apt-get install -y libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools -script: . /opt/qt56/bin/qt56-env.sh && make gcs CCACHE=ccache GCS_EXTRA_CONF=osg +script: . /opt/qt56/bin/qt56-env.sh && make gcs CCACHE=ccache GCS_EXTRA_CONF='osg osgearth' git: depth: 500 diff --git a/package/linux/debian/control b/package/linux/debian/control index 99d3e537e..3b0d49bc6 100644 --- a/package/linux/debian/control +++ b/package/linux/debian/control @@ -2,7 +2,7 @@ Source: Section: electronics Priority: optional Maintainer: The LibrePilot Project <> -Build-Depends: debhelper (>= 9), libudev-dev, libusb-1.0-0-dev, libsdl1.2-dev, python, libopenscenegraph-dev, qt5-default, qttools5-dev-tools, libqt5svg5-dev, qtdeclarative5-dev, qml-module-qtquick-controls, libqt5serialport5-dev, qtmultimedia5-dev, qtscript5-dev, libqt5opengl5-dev +Build-Depends: debhelper (>= 9), libudev-dev, libusb-1.0-0-dev, libsdl1.2-dev, python, libopenscenegraph-dev, libosgearth-dev, qt5-default, qttools5-dev-tools, libqt5svg5-dev, qtdeclarative5-dev, qml-module-qtquick-controls, libqt5serialport5-dev, qtmultimedia5-dev, qtscript5-dev, libqt5opengl5-dev Standards-Version: 3.9.5 Homepage: Vcs-Git: From c9fff7e16e0cb52d44e8dff3b4c4297cee8301a4 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sat, 16 Apr 2016 09:04:18 +0200 Subject: [PATCH 37/58] LP-151 OPLink: Allow custom Device ID or auto generated. --- flight/pios/common/pios_rfm22b.c | 61 +- flight/pios/inc/pios_rfm22b.h | 4 +- flight/pios/inc/pios_rfm22b_priv.h | 2 +- .../discoveryf4bare/firmware/pios_board.c | 8 +- .../boards/oplinkmini/firmware/pios_board.c | 8 +- .../boards/revolution/firmware/pios_board.c | 5 +- .../src/plugins/config/configoplinkwidget.cpp | 21 +- .../src/plugins/config/configoplinkwidget.h | 14 +- ground/gcs/src/plugins/config/oplink.ui | 777 ++++++++++-------- shared/uavobjectdefinition/oplinksettings.xml | 1 + 10 files changed, 513 insertions(+), 388 deletions(-) diff --git a/flight/pios/common/pios_rfm22b.c b/flight/pios/common/pios_rfm22b.c index 89724c563..7a3929607 100644 --- a/flight/pios/common/pios_rfm22b.c +++ b/flight/pios/common/pios_rfm22b.c @@ -7,7 +7,8 @@ * @{ * * @file pios_rfm22b.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief Implements a driver the the RFM22B driver * @see The GNU Public License (GPL) Version 3 * @@ -187,6 +188,7 @@ static enum pios_radio_event rfm22_fatal_error(struct pios_rfm22b_dev *rfm22b_de static void rfm22b_add_rx_status(struct pios_rfm22b_dev *rfm22b_dev, enum pios_rfm22b_rx_packet_status status); static void rfm22_setNominalCarrierFrequency(struct pios_rfm22b_dev *rfm22b_dev, uint8_t init_chan); static bool rfm22_setFreqHopChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t channel); +static void rfm22_generateDeviceID(struct pios_rfm22b_dev *rfm22b_dev); static void rfm22_updatePairStatus(struct pios_rfm22b_dev *radio_dev); static void rfm22_updateStats(struct pios_rfm22b_dev *rfm22b_dev); static bool rfm22_checkTimeOut(struct pios_rfm22b_dev *rfm22b_dev); @@ -446,18 +448,8 @@ int32_t PIOS_RFM22B_Init(uint32_t *rfm22b_id, uint32_t spi_id, uint32_t slave_nu // Create a semaphore to know if an ISR needs responding to vSemaphoreCreateBinary(rfm22b_dev->isrPending); - // Create our (hopefully) unique 32 bit id from the processor serial number. - uint8_t crcs[] = { 0, 0, 0, 0 }; - { - char serial_no_str[33]; - PIOS_SYS_SerialNumberGet(serial_no_str); - // Create a 32 bit value using 4 8 bit CRC values. - for (uint8_t i = 0; serial_no_str[i] != 0; ++i) { - crcs[i % 4] = PIOS_CRC_updateByte(crcs[i % 4], serial_no_str[i]); - } - } - rfm22b_dev->deviceID = crcs[0] | crcs[1] << 8 | crcs[2] << 16 | crcs[3] << 24; - DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); + // Create default (hopefully) unique 32 bit id from the processor serial number. + rfm22_generateDeviceID(rfm22b_dev); // Initialize the external interrupt. PIOS_EXTI_Init(cfg->exti_cfg); @@ -510,6 +502,26 @@ bool PIOS_RFM22_EXT_Int(void) return false; } + +/** + * Set the device ID for the RFM22B device. + * + * @param[in] rfm22b_id The RFM22B device index. + * + */ +void PIOS_RFM22B_SetDeviceID(uint32_t rfm22b_id, uint32_t custom_device_id) +{ + struct pios_rfm22b_dev *rfm22b_dev = (struct pios_rfm22b_dev *)rfm22b_id; + + if (custom_device_id > 0) { + rfm22b_dev->deviceID = custom_device_id; + } else { + rfm22_generateDeviceID(rfm22b_dev); + } + + DEBUG_PRINTF(2, "RF device ID: %x\n\r", rfm22b_dev->deviceID); +} + /** * Returns the unique device ID for the RFM22B device. * @@ -1711,6 +1723,29 @@ static bool rfm22_setFreqHopChannel(struct pios_rfm22b_dev *rfm22b_dev, uint8_t return true; } +/** + * Generate the unique device ID for the RFM22B device. + * + * @param[in] rfm22b_id The RFM22B device index. + * + */ +void rfm22_generateDeviceID(struct pios_rfm22b_dev *rfm22b_dev) +{ + // Create our (hopefully) unique 32 bit id from the processor serial number. + uint8_t crcs[] = { 0, 0, 0, 0 }; + { + char serial_no_str[33]; + PIOS_SYS_SerialNumberGet(serial_no_str); + // Create a 32 bit value using 4 8 bit CRC values. + for (uint8_t i = 0; serial_no_str[i] != 0; ++i) { + crcs[i % 4] = PIOS_CRC_updateByte(crcs[i % 4], serial_no_str[i]); + } + } + + rfm22b_dev->deviceID = crcs[0] | crcs[1] << 8 | crcs[2] << 16 | crcs[3] << 24; + DEBUG_PRINTF(2, "Generated RF device ID: %x\n\r", rfm22b_dev->deviceID); +} + /** * Read the RFM22B interrupt and device status registers * diff --git a/flight/pios/inc/pios_rfm22b.h b/flight/pios/inc/pios_rfm22b.h index 0c4593262..ec5d9d41e 100644 --- a/flight/pios/inc/pios_rfm22b.h +++ b/flight/pios/inc/pios_rfm22b.h @@ -7,7 +7,8 @@ * @{ * * @file pios_rfm22b.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief RFM22B functions header. * @see The GNU Public License (GPL) Version 3 * @@ -105,6 +106,7 @@ extern void PIOS_RFM22B_Reinit(uint32_t rfb22b_id); extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr); extern void PIOS_RFM22B_SetChannelConfig(uint32_t rfm22b_id, enum rfm22b_datarate datarate, uint8_t min_chan, uint8_t max_chan, bool coordinator, bool oneway, bool ppm_mode, bool ppm_only); extern void PIOS_RFM22B_SetCoordinatorID(uint32_t rfm22b_id, uint32_t coord_id); +extern void PIOS_RFM22B_SetDeviceID(uint32_t rfm22b_id, uint32_t device_id); extern uint32_t PIOS_RFM22B_DeviceID(uint32_t rfb22b_id); extern void PIOS_RFM22B_GetStats(uint32_t rfm22b_id, struct rfm22b_stats *stats); extern uint8_t PIOS_RFM22B_GetPairStats(uint32_t rfm22b_id, uint32_t *device_ids, int8_t *RSSIs, uint8_t max_pairs); diff --git a/flight/pios/inc/pios_rfm22b_priv.h b/flight/pios/inc/pios_rfm22b_priv.h index 47cf9d5c0..25cb754a0 100644 --- a/flight/pios/inc/pios_rfm22b_priv.h +++ b/flight/pios/inc/pios_rfm22b_priv.h @@ -674,7 +674,7 @@ struct pios_rfm22b_dev { // The device ID uint32_t deviceID; - // The coodinator ID (0 if this modem is a coordinator). + // The coordinator ID (0 if this modem is a coordinator). uint32_t coordinatorID; // The task handle diff --git a/flight/targets/boards/discoveryf4bare/firmware/pios_board.c b/flight/targets/boards/discoveryf4bare/firmware/pios_board.c index 9414d7f33..328e43a8a 100644 --- a/flight/targets/boards/discoveryf4bare/firmware/pios_board.c +++ b/flight/targets/boards/discoveryf4bare/firmware/pios_board.c @@ -1,8 +1,9 @@ /** ****************************************************************************** * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012 + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012 * @addtogroup OpenPilotSystem OpenPilot System * @{ * @addtogroup OpenPilotCore OpenPilot Core @@ -804,6 +805,7 @@ void PIOS_Board_Init(void) } /* Set the radio configuration parameters. */ + PIOS_RFM22B_SetDeviceID(pios_rfm22b_id, oplinkSettings.CustomDeviceID); PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, is_coordinator, is_oneway, ppm_mode, ppm_only); PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID); @@ -812,7 +814,7 @@ void PIOS_Board_Init(void) PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback); } - /* Set the modem Tx poer level */ + /* Set the modem Tx power level */ switch (oplinkSettings.MaxRFPower) { case OPLINKSETTINGS_MAXRFPOWER_125: PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); diff --git a/flight/targets/boards/oplinkmini/firmware/pios_board.c b/flight/targets/boards/oplinkmini/firmware/pios_board.c index 34d033db3..9ea6af908 100644 --- a/flight/targets/boards/oplinkmini/firmware/pios_board.c +++ b/flight/targets/boards/oplinkmini/firmware/pios_board.c @@ -6,7 +6,8 @@ * @{ * * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @brief Defines board specific static initializers for hardware for the OpenPilot board. * @see The GNU Public License (GPL) Version 3 * @@ -406,7 +407,7 @@ void PIOS_Board_Init(void) break; } - /* Set the modem Tx poer level */ + /* Set the modem Tx power level */ switch (oplinkSettings.MaxRFPower) { case OPLINKSETTINGS_MAXRFPOWER_125: PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); @@ -438,6 +439,7 @@ void PIOS_Board_Init(void) } // Set the radio configuration parameters. + PIOS_RFM22B_SetDeviceID(pios_rfm22b_id, oplinkSettings.CustomDeviceID); PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID); PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, is_coordinator, is_oneway, ppm_mode, ppm_only); @@ -446,7 +448,7 @@ void PIOS_Board_Init(void) PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback); } - // Reinitilize the modem to affect te changes. + // Reinitialize the modem to affect the changes. PIOS_RFM22B_Reinit(pios_rfm22b_id); } else { oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED; diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index 018d7a397..08b792f6b 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -1,7 +1,7 @@ /** ****************************************************************************** * @file pios_board.c - * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015. + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015-2016. * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. * PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012 * @addtogroup OpenPilotSystem OpenPilot System @@ -885,6 +885,7 @@ void PIOS_Board_Init(void) } /* Set the radio configuration parameters. */ + PIOS_RFM22B_SetDeviceID(pios_rfm22b_id, oplinkSettings.CustomDeviceID); PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID); PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, is_coordinator, is_oneway, ppm_mode, ppm_only); @@ -893,7 +894,7 @@ void PIOS_Board_Init(void) PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback); } - /* Set the modem Tx poer level */ + /* Set the modem Tx power level */ switch (oplinkSettings.MaxRFPower) { case OPLINKSETTINGS_MAXRFPOWER_125: PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); diff --git a/ground/gcs/src/plugins/config/configoplinkwidget.cpp b/ground/gcs/src/plugins/config/configoplinkwidget.cpp index 31b45dbe3..8417aca4e 100644 --- a/ground/gcs/src/plugins/config/configoplinkwidget.cpp +++ b/ground/gcs/src/plugins/config/configoplinkwidget.cpp @@ -1,14 +1,14 @@ /** ****************************************************************************** * - * @file configtxpidswidget.cpp - * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015. + * @file configoplinkwidget.cpp + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015-2016. * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin * @{ - * @brief The Configuration Gadget used to configure the PipXtreme + * @brief The Configuration Gadget used to configure the OPLink and Revo modem *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -80,6 +80,7 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren addWidgetBinding("OPLinkSettings", "PPMOnly", m_oplink->PPMOnly); addWidgetBinding("OPLinkSettings", "PPM", m_oplink->PPM); addWidgetBinding("OPLinkSettings", "ComSpeed", m_oplink->ComSpeed); + addWidgetBinding("OPLinkSettings", "CustomDeviceID", m_oplink->CustomDeviceID); addWidgetBinding("OPLinkStatus", "DeviceID", m_oplink->DeviceID); addWidgetBinding("OPLinkStatus", "RxGood", m_oplink->Good); @@ -112,6 +113,9 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren connect(m_oplink->PPMOnly, SIGNAL(toggled(bool)), this, SLOT(ppmOnlyChanged())); connect(m_oplink->MinimumChannel, SIGNAL(valueChanged(int)), this, SLOT(minChannelChanged())); connect(m_oplink->MaximumChannel, SIGNAL(valueChanged(int)), this, SLOT(maxChannelChanged())); + connect(m_oplink->CustomDeviceID, SIGNAL(editingFinished()), this, SLOT(updateCustomDeviceID())); + + m_oplink->CustomDeviceID->setInputMask("HHHHHHHH"); m_oplink->MinimumChannel->setKeyboardTracking(false); m_oplink->MaximumChannel->setKeyboardTracking(false); @@ -247,7 +251,6 @@ void ConfigOPLinkWidget::updateSettings(UAVObject *object) if (!settingsUpdated) { settingsUpdated = true; - // Enable components based on the board type connected. UAVObjectField *board_type_field = oplinkStatusObj->getField("BoardType"); switch (board_type_field->getValue().toInt()) { @@ -294,6 +297,7 @@ void ConfigOPLinkWidget::updateSettings(UAVObject *object) void ConfigOPLinkWidget::updateEnableControls() { + updateCustomDeviceID(); enableControls(true); ppmOnlyChanged(); } @@ -384,6 +388,15 @@ void ConfigOPLinkWidget::channelChanged(bool isMax) m_oplink->MaxFreq->setText("(" + QString::number(maxFrequency, 'f', 3) + " MHz)"); } +void ConfigOPLinkWidget::updateCustomDeviceID() +{ + bool customDeviceIDNotSet = (m_oplink->CustomDeviceID->text() == "0"); + + if (settingsUpdated && customDeviceIDNotSet) { + m_oplink->CustomDeviceID->clear(); + m_oplink->CustomDeviceID->setPlaceholderText(m_oplink->DeviceID->text()); + } +} /** @} @} diff --git a/ground/gcs/src/plugins/config/configoplinkwidget.h b/ground/gcs/src/plugins/config/configoplinkwidget.h index 032722099..620b1c52d 100644 --- a/ground/gcs/src/plugins/config/configoplinkwidget.h +++ b/ground/gcs/src/plugins/config/configoplinkwidget.h @@ -1,13 +1,14 @@ /** ****************************************************************************** * - * @file configpipxtremewidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @file configoplinkwidget.h + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin * @{ - * @brief The Configuration Gadget used to configure PipXtreme + * @brief The Configuration Gadget used to configure the OPLink and Revo modem *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,8 +25,8 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef CONFIGPIPXTREMEWIDGET_H -#define CONFIGPIPXTREMEWIDGET_H +#ifndef CONFIGOPLINKWIDGET_H +#define CONFIGOPLINKWIDGET_H #include "configtaskwidget.h" @@ -65,7 +66,8 @@ private slots: void ppmOnlyChanged(); void minChannelChanged(); void maxChannelChanged(); + void updateCustomDeviceID(); void channelChanged(bool isMax); }; -#endif // CONFIGTXPIDWIDGET_H +#endif // CONFIGOPLINKWIDGET_H diff --git a/ground/gcs/src/plugins/config/oplink.ui b/ground/gcs/src/plugins/config/oplink.ui index 9ee795fdb..db795b7ce 100644 --- a/ground/gcs/src/plugins/config/oplink.ui +++ b/ground/gcs/src/plugins/config/oplink.ui @@ -54,360 +54,6 @@ - - - - - 0 - 0 - - - - - 50 - false - - - - Configuration - - - - - - Com speed in bps. - - - - - - - - 50 - false - - - - Com Speed - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - VCP Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the flexi port - - - - - - - - 50 - false - - - - Main Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the main port - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the USB virtual com port - - - - - - - - 16777215 - 16777215 - - - - Set the maximum TX output power the modem will use (mW) - - - Qt::LeftToRight - - - 0 - - - - - - - - 50 - false - - - - Max Power - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - 50 - false - - - - FlexiIO Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 60 - 16777215 - - - - - 50 - false - - - - Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. - - - 250 - - - - - - - - 50 - false - - - - Flexi Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - Max Chan - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - Min Chan - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 60 - 16777215 - - - - - 50 - false - - - - Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. - - - 250 - - - - - - - - 50 - false - - - - This modem will be a coordinator and other modems will bind to it. - - - Coordinator - - - - - - - - 110 - 16777215 - - - - 440.000 (MHz) - - - - - - - - 110 - 16777215 - - - - 430.000 (MHz) - - - - - - - - 50 - false - - - - false - - - If selected, data will only be transmitted from the coordinator to the Rx modem. - - - One-Way - - - - - - - - 50 - false - - - - Only PPM packets will be transmitted. - - - PPM Only - - - - - - - - 50 - false - - - - PPM packets will be received by this modem. Must be selected if Coordinator modem is configured for PPM. - - - PPM - - - - - - @@ -759,6 +405,9 @@ false + + 8 + false @@ -769,7 +418,7 @@ true - 12345678 + AA00FF99 @@ -1789,6 +1438,424 @@ + + + + + 0 + 0 + + + + + 50 + false + + + + Configuration + + + + + + + 50 + false + + + + This modem will be a coordinator and other modems will bind to it. + + + Coordinator + + + + + + + Com speed in bps. + + + + + + + + 50 + false + + + + Com Speed + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + VCP Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the flexi port + + + + + + + + 50 + false + + + + Main Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the main port + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the USB virtual com port + + + + + + + + + + + 16777215 + 16777215 + + + + Set the maximum TX output power the modem will use (mW) + + + Qt::LeftToRight + + + 0 + + + + + + + + 50 + false + + + + Max Power + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 60 + 16777215 + + + + + 50 + false + + + + Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. + + + 250 + + + + + + + + 50 + false + + + + FlexiIO Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + Flexi Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 60 + 16777215 + + + + + 50 + false + + + + Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. + + + 250 + + + + + + + + 50 + false + + + + Max Chan + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + Min Chan + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 110 + 16777215 + + + + 430.000 (MHz) + + + + + + + + 50 + false + + + + false + + + If selected, data will only be transmitted from the coordinator to the Rx modem. + + + One-Way + + + + + + + + 50 + false + + + + Only PPM packets will be transmitted. + + + PPM Only + + + + + + + + 50 + false + + + + PPM packets will be received by this modem. Must be selected if Coordinator modem is configured for PPM. + + + PPM + + + + + + + + 110 + 16777215 + + + + 440.000 (MHz) + + + + + + + + 0 + 0 + + + + + 101 + 16777215 + + + + + 50 + false + + + + Enter your custom ID for this device as hexadecimal value, +this allow device clones. Be sure only one same Device ID transmit once! +Leave blank for Device ID autogenerated. + + + 8 + + + true + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + AA00FF99 + + + Qt::LogicalMoveStyle + + + false + + + + + + + + 50 + false + + + + Device ID + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + diff --git a/shared/uavobjectdefinition/oplinksettings.xml b/shared/uavobjectdefinition/oplinksettings.xml index 6e5674c8f..cc2b46a0e 100644 --- a/shared/uavobjectdefinition/oplinksettings.xml +++ b/shared/uavobjectdefinition/oplinksettings.xml @@ -13,6 +13,7 @@ + From 8ac0bc38aa0621492922dcb6fee739bf3873168f Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 20 Apr 2016 18:23:10 +0200 Subject: [PATCH 38/58] LP-292 Oplink tab cleanup, remove unused buttons, remote monitoring. Update statusTip to toolTip. --- .../src/plugins/config/configoplinkwidget.cpp | 95 +- .../src/plugins/config/configoplinkwidget.h | 2 +- ground/gcs/src/plugins/config/oplink.ui | 1014 ++++++++--------- 3 files changed, 465 insertions(+), 646 deletions(-) diff --git a/ground/gcs/src/plugins/config/configoplinkwidget.cpp b/ground/gcs/src/plugins/config/configoplinkwidget.cpp index 8417aca4e..0a744de04 100644 --- a/ground/gcs/src/plugins/config/configoplinkwidget.cpp +++ b/ground/gcs/src/plugins/config/configoplinkwidget.cpp @@ -103,19 +103,15 @@ ConfigOPLinkWidget::ConfigOPLinkWidget(QWidget *parent) : ConfigTaskWidget(paren addWidgetBinding("OPLinkStatus", "RXPacketRate", m_oplink->RXPacketRate); addWidgetBinding("OPLinkStatus", "TXPacketRate", m_oplink->TXPacketRate); - // Connect the bind buttons - connect(m_oplink->Bind1, SIGNAL(clicked()), this, SLOT(bind())); - connect(m_oplink->Bind2, SIGNAL(clicked()), this, SLOT(bind())); - connect(m_oplink->Bind3, SIGNAL(clicked()), this, SLOT(bind())); - connect(m_oplink->Bind4, SIGNAL(clicked()), this, SLOT(bind())); - // Connect the selection changed signals. connect(m_oplink->PPMOnly, SIGNAL(toggled(bool)), this, SLOT(ppmOnlyChanged())); + connect(m_oplink->Coordinator, SIGNAL(toggled(bool)), this, SLOT(updateCoordID())); connect(m_oplink->MinimumChannel, SIGNAL(valueChanged(int)), this, SLOT(minChannelChanged())); connect(m_oplink->MaximumChannel, SIGNAL(valueChanged(int)), this, SLOT(maxChannelChanged())); connect(m_oplink->CustomDeviceID, SIGNAL(editingFinished()), this, SLOT(updateCustomDeviceID())); m_oplink->CustomDeviceID->setInputMask("HHHHHHHH"); + m_oplink->CoordID->setInputMask("HHHHHHHH"); m_oplink->MinimumChannel->setKeyboardTracking(false); m_oplink->MaximumChannel->setKeyboardTracking(false); @@ -148,53 +144,10 @@ void ConfigOPLinkWidget::updateStatus(UAVObject *object) UAVObjectField *linkField = object->getField("LinkState"); m_oplink->LinkState->setText(linkField->getValue().toString()); bool linkConnected = (linkField->getValue() == linkField->getOptions().at(OPLinkStatus::LINKSTATE_CONNECTED)); - bool modemEnabled = linkConnected || (linkField->getValue() == linkField->getOptions().at(OPLinkStatus::LINKSTATE_DISCONNECTED)) || - (linkField->getValue() == linkField->getOptions().at(OPLinkStatus::LINKSTATE_ENABLED)); - UAVObjectField *pairRssiField = object->getField("PairSignalStrengths"); - - bool bound; - bool ok; - quint32 boundPairId = m_oplink->CoordID->text().toUInt(&ok, 16); - - // Update the detected devices. - UAVObjectField *pairIdField = object->getField("PairIDs"); - quint32 pairid = pairIdField->getValue(0).toUInt(); - bound = (pairid == boundPairId); - m_oplink->PairID1->setText(QString::number(pairid, 16).toUpper()); - m_oplink->PairID1->setEnabled(false); - m_oplink->Bind1->setText(bound ? tr("Unbind") : tr("Bind")); - m_oplink->Bind1->setEnabled(pairid && modemEnabled); - m_oplink->PairSignalStrengthBar1->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(0).toInt()); + m_oplink->PairSignalStrengthBar1->setValue(linkConnected ? m_oplink->RSSI->text().toInt() : -127); m_oplink->PairSignalStrengthLabel1->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar1->value())); - pairid = pairIdField->getValue(1).toUInt(); - bound = (pairid == boundPairId); - m_oplink->PairID2->setText(QString::number(pairid, 16).toUpper()); - m_oplink->PairID2->setEnabled(false); - m_oplink->Bind2->setText(bound ? tr("Unbind") : tr("Bind")); - m_oplink->Bind2->setEnabled(pairid && modemEnabled); - m_oplink->PairSignalStrengthBar2->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(1).toInt()); - m_oplink->PairSignalStrengthLabel2->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar2->value())); - - pairid = pairIdField->getValue(2).toUInt(); - bound = (pairid == boundPairId); - m_oplink->PairID3->setText(QString::number(pairid, 16).toUpper()); - m_oplink->PairID3->setEnabled(false); - m_oplink->Bind3->setText(bound ? tr("Unbind") : tr("Bind")); - m_oplink->Bind3->setEnabled(pairid && modemEnabled); - m_oplink->PairSignalStrengthBar3->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(2).toInt()); - m_oplink->PairSignalStrengthLabel3->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar3->value())); - - pairid = pairIdField->getValue(3).toUInt(); - bound = (pairid == boundPairId); - m_oplink->PairID4->setText(QString::number(pairid, 16).toUpper()); - m_oplink->PairID4->setEnabled(false); - m_oplink->Bind4->setText(bound ? tr("Unbind") : tr("Bind")); - m_oplink->Bind4->setEnabled(pairid && modemEnabled); - m_oplink->PairSignalStrengthBar4->setValue(((bound && !linkConnected) || !modemEnabled) ? -127 : pairRssiField->getValue(3).toInt()); - m_oplink->PairSignalStrengthLabel4->setText(QString("%1dB").arg(m_oplink->PairSignalStrengthBar4->value())); - // Update the Description field // TODO use UAVObjectUtilManager::descriptionToStructure() UAVObjectField *descField = object->getField("Description"); @@ -297,6 +250,7 @@ void ConfigOPLinkWidget::updateSettings(UAVObject *object) void ConfigOPLinkWidget::updateEnableControls() { + updateCoordID(); updateCustomDeviceID(); enableControls(true); ppmOnlyChanged(); @@ -309,32 +263,6 @@ void ConfigOPLinkWidget::disconnected() } } -void ConfigOPLinkWidget::bind() -{ - QPushButton *bindButton = qobject_cast(sender()); - - if (bindButton) { - QLineEdit *editField = NULL; - if (bindButton == m_oplink->Bind1) { - editField = m_oplink->PairID1; - } else if (bindButton == m_oplink->Bind2) { - editField = m_oplink->PairID2; - } else if (bindButton == m_oplink->Bind3) { - editField = m_oplink->PairID3; - } else if (bindButton == m_oplink->Bind4) { - editField = m_oplink->PairID4; - } - Q_ASSERT(editField); - bool ok; - quint32 pairid = editField->text().toUInt(&ok, 16); - if (ok) { - quint32 boundPairId = m_oplink->CoordID->text().toUInt(&ok, 16); - (pairid != boundPairId) ? m_oplink->CoordID->setText(QString::number(pairid, 16).toUpper()) : m_oplink->CoordID->setText("0"); - } - QMessageBox::information(this, tr("Information"), tr("To apply the changes when binding/unbinding the board must be rebooted or power cycled."), QMessageBox::Ok); - } -} - void ConfigOPLinkWidget::ppmOnlyChanged() { bool is_ppm_only = m_oplink->PPMOnly->isChecked(); @@ -388,13 +316,26 @@ void ConfigOPLinkWidget::channelChanged(bool isMax) m_oplink->MaxFreq->setText("(" + QString::number(maxFrequency, 'f', 3) + " MHz)"); } +void ConfigOPLinkWidget::updateCoordID() +{ + bool is_coordinator = m_oplink->Coordinator->isChecked(); + bool coordinatorNotSet = (m_oplink->CoordID->text() == "0"); + + if (settingsUpdated && coordinatorNotSet) { + m_oplink->CoordID->clear(); + m_oplink->CoordID->setPlaceholderText("SetCoordID"); + } + m_oplink->CoordID->setVisible(!is_coordinator); + m_oplink->CoordIDLabel->setVisible(!is_coordinator); +} + void ConfigOPLinkWidget::updateCustomDeviceID() { bool customDeviceIDNotSet = (m_oplink->CustomDeviceID->text() == "0"); if (settingsUpdated && customDeviceIDNotSet) { m_oplink->CustomDeviceID->clear(); - m_oplink->CustomDeviceID->setPlaceholderText(m_oplink->DeviceID->text()); + m_oplink->CustomDeviceID->setPlaceholderText("AutoGenerated"); } } /** diff --git a/ground/gcs/src/plugins/config/configoplinkwidget.h b/ground/gcs/src/plugins/config/configoplinkwidget.h index 620b1c52d..feeb529aa 100644 --- a/ground/gcs/src/plugins/config/configoplinkwidget.h +++ b/ground/gcs/src/plugins/config/configoplinkwidget.h @@ -62,10 +62,10 @@ protected: private slots: void disconnected(); - void bind(); void ppmOnlyChanged(); void minChannelChanged(); void maxChannelChanged(); + void updateCoordID(); void updateCustomDeviceID(); void channelChanged(bool isMax); }; diff --git a/ground/gcs/src/plugins/config/oplink.ui b/ground/gcs/src/plugins/config/oplink.ui index db795b7ce..9a03a10ad 100644 --- a/ground/gcs/src/plugins/config/oplink.ui +++ b/ground/gcs/src/plugins/config/oplink.ui @@ -54,303 +54,6 @@ - - - - Remote modems - - - - - - - 50 - false - - - - -100dB - - - - - - - -127 - - - 0 - - - 0 - - - false - - - %v dBm - - - - - - - - 50 - false - - - - -100dB - - - - - - - - 100 - 16777215 - - - - - 50 - false - - - - - - - - -127 - - - 0 - - - 0 - - - false - - - %v dBm - - - - - - - - 100 - 16777215 - - - - - 50 - false - - - - - - - - -127 - - - 0 - - - -127 - - - false - - - %v dBm - - - - - - - - 50 - false - - - - -100dB - - - - - - - -127 - - - 0 - - - 0 - - - false - - - %v dBm - - - - - - - - 50 - false - - - - -100dB - - - - - - - - 100 - 16777215 - - - - - 50 - false - - - - - - - - - 100 - 16777215 - - - - - 50 - false - - - - 12345678 - - - - - - - - 50 - false - - - - Bind - - - - - - - - 50 - false - - - - Bind - - - - - - - - 50 - false - - - - Bind - - - - - - - - 50 - false - - - - Bind - - - - - - - - 50 - false - - - - Qt::LeftToRight - - - Coordinator ID - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 100 - 16777215 - - - - - 50 - false - - - - <html><head/><body><p>This is the coordinator id we currently are bound to.</p><p>To manually bind to a specific coordinator, just type</p><p>or paste its device id in this box and save.</p><p>The device must be rebooted for the binding to take place.</p></body></html> - - - 8 - - - - - - @@ -1441,7 +1144,7 @@ - + 0 0 @@ -1456,209 +1159,7 @@ Configuration - - - - - 50 - false - - - - This modem will be a coordinator and other modems will bind to it. - - - Coordinator - - - - - - - Com speed in bps. - - - - - - - - 50 - false - - - - Com Speed - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - VCP Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the flexi port - - - - - - - - 50 - false - - - - Main Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the main port - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the USB virtual com port - - - - - - - - - - - 16777215 - 16777215 - - - - Set the maximum TX output power the modem will use (mW) - - - Qt::LeftToRight - - - 0 - - - - - - - - 50 - false - - - - Max Power - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 60 - 16777215 - - - - - 50 - false - - - - Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. - - - 250 - - - - - - - - 50 - false - - - - FlexiIO Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - Flexi Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - + @@ -1680,8 +1181,54 @@ - - + + + + Com speed in bps. + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the main port + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the USB virtual com port + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the flexi port + + + + + 50 @@ -1689,15 +1236,37 @@ - Max Chan + FlexiIO Port Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - + + + + + 50 + false + + + + Flexi Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + 0 + 0 + + 50 @@ -1712,7 +1281,7 @@ - + @@ -1725,58 +1294,7 @@ - - - - - 50 - false - - - - false - - - If selected, data will only be transmitted from the coordinator to the Rx modem. - - - One-Way - - - - - - - - 50 - false - - - - Only PPM packets will be transmitted. - - - PPM Only - - - - - - - - 50 - false - - - - PPM packets will be received by this modem. Must be selected if Coordinator modem is configured for PPM. - - - PPM - - - - + @@ -1789,7 +1307,242 @@ - + + + + + + + + 60 + 16777215 + + + + + 50 + false + + + + Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. + + + 250 + + + + + + + + 50 + false + + + + VCP Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + Com Speed + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + Main Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Set the maximum TX output power the modem will use (mW) +0 to disable the modem. + + + Qt::LeftToRight + + + 0 + + + + + + + + 50 + false + + + + Max Power + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 50 + false + + + + Max Chan + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + Only PPM packets will be transmitted and baudrate is set to 9600bauds by default + + + PPM Only + + + + + + + + 50 + false + + + + This modem will be a coordinator and other modems will bind to it. + + + Coordinator + + + + + + + + 50 + false + + + + Qt::LeftToRight + + + Coordinator ID + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 110 + 16777215 + + + + + 50 + false + + + + <html><head/><body><p>This is the coordinator id we currently are bound to.</p><p>To manually bind to a specific coordinator, just type</p><p>or paste its device id in this box and save.</p><p>The device must be rebooted for the binding to take place.</p></body></html> + + + 8 + + + FFFFFFFF + + + Qt::LogicalMoveStyle + + + false + + + + + + + + 50 + false + + + + Device ID + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + @@ -1799,7 +1552,7 @@ - 101 + 110 16777215 @@ -1837,8 +1590,81 @@ Leave blank for Device ID autogenerated. - - + + + + + 50 + false + + + + false + + + If selected, data will only be transmitted from the coordinator to the Rx modem. + + + One-Way + + + + + + + + 50 + false + + + + PPM packets will be received by this modem. +Must be selected if Coordinator modem is configured for PPM. + + + PPM + + + + + + + + + + + 0 + 0 + + + + Remote modem + + + + + + RX level + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 0 + + 50 @@ -1846,13 +1672,69 @@ Leave blank for Device ID autogenerated. - Device ID + -100dB - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + Qt::AlignCenter + + + + + + + 0 + 0 + + + + + 30 + 16777215 + + + + + 0 + 0 + + + + Qt::RightToLeft + + + false + + + -127 + + + 0 + + + -127 + + + Qt::AlignCenter + + + false + + + Qt::Vertical + + + false + + + %v dBm + + + + + @@ -1953,10 +1835,6 @@ Leave blank for Device ID autogenerated. - PairID1 - PairID2 - PairID3 - PairID4 FirmwareVersion SerialNumber Apply From 553f2e90bba5e01eebf8e259b916bdb57d17f9a7 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 21 Apr 2016 14:11:49 +0200 Subject: [PATCH 39/58] LP-292 Move Rx level to the right, fix alignements and typos. --- .../src/plugins/config/configoplinkwidget.cpp | 57 +- .../src/plugins/config/configoplinkwidget.h | 1 + ground/gcs/src/plugins/config/oplink.ui | 1145 +++++++++-------- 3 files changed, 684 insertions(+), 519 deletions(-) diff --git a/ground/gcs/src/plugins/config/configoplinkwidget.cpp b/ground/gcs/src/plugins/config/configoplinkwidget.cpp index 0a744de04..8fea81c2f 100644 --- a/ground/gcs/src/plugins/config/configoplinkwidget.cpp +++ b/ground/gcs/src/plugins/config/configoplinkwidget.cpp @@ -216,7 +216,7 @@ void ConfigOPLinkWidget::updateSettings(UAVObject *object) m_oplink->VCPPortLabel->setVisible(false); m_oplink->FlexiIOPort->setVisible(false); m_oplink->FlexiIOPortLabel->setVisible(false); - m_oplink->PPM->setVisible(true); + m_oplink->PPM->setEnabled(true); break; case 0x03: // OPLinkMini m_oplink->MainPort->setVisible(true); @@ -227,7 +227,9 @@ void ConfigOPLinkWidget::updateSettings(UAVObject *object) m_oplink->VCPPortLabel->setVisible(true); m_oplink->FlexiIOPort->setVisible(false); m_oplink->FlexiIOPortLabel->setVisible(false); - m_oplink->PPM->setVisible(false); + m_oplink->PPM->setEnabled(false); + connect(m_oplink->MainPort, SIGNAL(currentIndexChanged(int)), this, SLOT(updatePPMOptions())); + connect(m_oplink->FlexiPort, SIGNAL(currentIndexChanged(int)), this, SLOT(updatePPMOptions())); break; case 0x0A: // OPLink? m_oplink->MainPort->setVisible(true); @@ -238,7 +240,9 @@ void ConfigOPLinkWidget::updateSettings(UAVObject *object) m_oplink->VCPPortLabel->setVisible(true); m_oplink->FlexiIOPort->setVisible(true); m_oplink->FlexiIOPortLabel->setVisible(true); - m_oplink->PPM->setVisible(false); + m_oplink->PPM->setEnabled(false); + connect(m_oplink->MainPort, SIGNAL(currentIndexChanged(int)), this, SLOT(updatePPMOptions())); + connect(m_oplink->FlexiPort, SIGNAL(currentIndexChanged(int)), this, SLOT(updatePPMOptions())); break; default: // This shouldn't happen. @@ -250,9 +254,10 @@ void ConfigOPLinkWidget::updateSettings(UAVObject *object) void ConfigOPLinkWidget::updateEnableControls() { - updateCoordID(); - updateCustomDeviceID(); enableControls(true); + updatePPMOptions(); + updateCustomDeviceID(); + updateCoordID(); ppmOnlyChanged(); } @@ -263,11 +268,45 @@ void ConfigOPLinkWidget::disconnected() } } +void ConfigOPLinkWidget::updatePPMOptions() +{ + bool is_oplm = m_oplink->MainPort->isVisible(); + + if (!is_oplm) { + return; + } + + bool is_coordinator = m_oplink->Coordinator->isChecked(); + bool is_ppm_active = ((isComboboxOptionSelected(m_oplink->MainPort, OPLinkSettings::MAINPORT_PPM)) || + (isComboboxOptionSelected(m_oplink->FlexiPort, OPLinkSettings::FLEXIPORT_PPM))); + + m_oplink->PPM->setEnabled(false); + m_oplink->PPM->setChecked(is_ppm_active); + m_oplink->PPMOnly->setEnabled(is_ppm_active); + + if (!is_ppm_active) { + m_oplink->PPMOnly->setChecked(false); + QString selectPort = tr("Please select a port for PPM function."); + m_oplink->PPMOnly->setToolTip(selectPort); + m_oplink->PPM->setToolTip(selectPort); + } else { + if (is_coordinator) { + m_oplink->PPMOnly->setToolTip(tr("Only PPM packets will be transmitted and baudrate set to 9600 bauds by default.")); + m_oplink->PPM->setToolTip(tr("PPM packets will be transmitted by this modem.")); + } else { + m_oplink->PPMOnly->setToolTip(tr("Only PPM packets will be received and baudrate set to 9600 bauds by default.")); + m_oplink->PPM->setToolTip(tr("PPM packets will be received by this modem.")); + } + } +} + + void ConfigOPLinkWidget::ppmOnlyChanged() { bool is_ppm_only = m_oplink->PPMOnly->isChecked(); + bool is_oplm = m_oplink->MainPort->isVisible(); - m_oplink->PPM->setEnabled(!is_ppm_only); + m_oplink->PPM->setEnabled(!is_ppm_only && !is_oplm); m_oplink->OneWayLink->setEnabled(!is_ppm_only); m_oplink->ComSpeed->setEnabled(!is_ppm_only); } @@ -323,10 +362,8 @@ void ConfigOPLinkWidget::updateCoordID() if (settingsUpdated && coordinatorNotSet) { m_oplink->CoordID->clear(); - m_oplink->CoordID->setPlaceholderText("SetCoordID"); } - m_oplink->CoordID->setVisible(!is_coordinator); - m_oplink->CoordIDLabel->setVisible(!is_coordinator); + m_oplink->CoordID->setEnabled(!is_coordinator); } void ConfigOPLinkWidget::updateCustomDeviceID() @@ -335,7 +372,7 @@ void ConfigOPLinkWidget::updateCustomDeviceID() if (settingsUpdated && customDeviceIDNotSet) { m_oplink->CustomDeviceID->clear(); - m_oplink->CustomDeviceID->setPlaceholderText("AutoGenerated"); + m_oplink->CustomDeviceID->setPlaceholderText("AutoGen"); } } /** diff --git a/ground/gcs/src/plugins/config/configoplinkwidget.h b/ground/gcs/src/plugins/config/configoplinkwidget.h index feeb529aa..ce0cc6643 100644 --- a/ground/gcs/src/plugins/config/configoplinkwidget.h +++ b/ground/gcs/src/plugins/config/configoplinkwidget.h @@ -62,6 +62,7 @@ protected: private slots: void disconnected(); + void updatePPMOptions(); void ppmOnlyChanged(); void minChannelChanged(); void maxChannelChanged(); diff --git a/ground/gcs/src/plugins/config/oplink.ui b/ground/gcs/src/plugins/config/oplink.ui index 9a03a10ad..c09733857 100644 --- a/ground/gcs/src/plugins/config/oplink.ui +++ b/ground/gcs/src/plugins/config/oplink.ui @@ -18,7 +18,7 @@ - OPLink configuration + OPLink Configuration @@ -36,7 +36,7 @@ 0 - + QFrame::NoFrame @@ -54,7 +54,20 @@ - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + @@ -62,6 +75,12 @@ 0 + + + 1050 + 16777215 + + 50 @@ -168,7 +187,7 @@ - The modems current state + The modems current state. Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -860,7 +879,7 @@ - Tx Failure + TX Failure Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -1141,495 +1160,7 @@ - - - - - 0 - 0 - - - - - 50 - false - - - - Configuration - - - - - - - 60 - 16777215 - - - - - 50 - false - - - - Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. - - - 250 - - - - - - - Com speed in bps. - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the main port - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the USB virtual com port - - - - - - - - 16777215 - 16777215 - - - - Choose the function for the flexi port - - - - - - - - 50 - false - - - - FlexiIO Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - Flexi Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 50 - false - - - - Min Chan - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 110 - 16777215 - - - - 430.000 (MHz) - - - - - - - - 110 - 16777215 - - - - 440.000 (MHz) - - - - - - - - - - - 60 - 16777215 - - - - - 50 - false - - - - Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. - - - 250 - - - - - - - - 50 - false - - - - VCP Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - Com Speed - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - Main Port - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 16777215 - 16777215 - - - - Set the maximum TX output power the modem will use (mW) -0 to disable the modem. - - - Qt::LeftToRight - - - 0 - - - - - - - - 50 - false - - - - Max Power - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 50 - false - - - - Max Chan - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 50 - false - - - - Only PPM packets will be transmitted and baudrate is set to 9600bauds by default - - - PPM Only - - - - - - - - 50 - false - - - - This modem will be a coordinator and other modems will bind to it. - - - Coordinator - - - - - - - - 50 - false - - - - Qt::LeftToRight - - - Coordinator ID - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 110 - 16777215 - - - - - 50 - false - - - - <html><head/><body><p>This is the coordinator id we currently are bound to.</p><p>To manually bind to a specific coordinator, just type</p><p>or paste its device id in this box and save.</p><p>The device must be rebooted for the binding to take place.</p></body></html> - - - 8 - - - FFFFFFFF - - - Qt::LogicalMoveStyle - - - false - - - - - - - - 50 - false - - - - Device ID - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 110 - 16777215 - - - - - 50 - false - - - - Enter your custom ID for this device as hexadecimal value, -this allow device clones. Be sure only one same Device ID transmit once! -Leave blank for Device ID autogenerated. - - - 8 - - - true - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - AA00FF99 - - - Qt::LogicalMoveStyle - - - false - - - - - - - - 50 - false - - - - false - - - If selected, data will only be transmitted from the coordinator to the Rx modem. - - - One-Way - - - - - - - - 50 - false - - - - PPM packets will be received by this modem. -Must be selected if Coordinator modem is configured for PPM. - - - PPM - - - - - - - + @@ -1637,20 +1168,19 @@ Must be selected if Coordinator modem is configured for PPM. 0 + + + 150 + 16777215 + + - Remote modem + RX Level + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - RX level - - - Qt::AlignCenter - - - @@ -1661,7 +1191,7 @@ Must be selected if Coordinator modem is configured for PPM. - 0 + 100 0 @@ -1684,7 +1214,7 @@ Must be selected if Coordinator modem is configured for PPM. - + 0 0 @@ -1738,6 +1268,603 @@ Must be selected if Coordinator modem is configured for PPM. + + + + true + + + + 0 + 0 + + + + + 900 + 16777215 + + + + + 50 + false + + + + Configuration + + + + + + Com speed in bps. + + + + + + + + 50 + false + + + + FlexiIO Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the main port. + + + + + + + + 16777215 + 16777215 + + + + Set the maximum TX output power the modem will use (mW) +0 to disable the modem. + + + Qt::LeftToRight + + + 0 + + + + + + + + 50 + false + + + + Main Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + 0 + 0 + + + + + 50 + false + + + + Max Power + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + Com Speed + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 50 + false + + + + Only PPM packets will be transmitted and baudrate set to 9600bauds by default. + + + PPM Only + + + + + + + + 0 + 0 + + + + + 50 + false + + + + PPM packets will be received by this modem. +Must be selected if Coordinator modem is configured for PPM. + + + PPM + + + + + + + + 50 + false + + + + Qt::LeftToRight + + + Coordinator ID + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 50 + false + + + + Device ID + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 90 + 16777215 + + + + + 50 + false + + + + Enter your custom ID for this device as a hexadecimal value, +this allows device clones. Be sure only one device with this +ID transmits at the same time! +Leave blank to use autogenerated Device ID. + + + 8 + + + true + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + AA00FF99 + + + Qt::LogicalMoveStyle + + + false + + + + + + + + 0 + 0 + + + + + 90 + 16777215 + + + + + 50 + false + + + + This is the coordinator ID we currently are bound to. +To manually bind to a specific coordinator, just type +or paste its device ID in this box and save. +The device must be rebooted for the binding to take place. + + + 8 + + + Qt::LogicalMoveStyle + + + false + + + + + + + + 0 + 0 + + + + + 50 + false + + + + false + + + If selected, data will only be transmitted from the coordinator to the Rx modem. + + + One-Way + + + + + + + + 0 + 0 + + + + + 0 + 32 + + + + + 50 + false + + + + This modem will be a coordinator and other modems will bind to it. + + + Coordinator + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the flexi port. + + + + + + + + 50 + false + + + + Flexi Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 16777215 + 16777215 + + + + Choose the function for the USB virtual com port. + + + + + + + + 50 + false + + + + VCP Port + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 80 + 0 + + + + + 50 + false + + + + Max Chan + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 80 + 0 + + + + + 50 + false + + + + Min Chan + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + 0 + 0 + + + + + 60 + 16777215 + + + + + 50 + false + + + + Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. + + + 250 + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + 430.000 (MHz) + + + + + + + + + + + + 0 + 0 + + + + + 60 + 16777215 + + + + + 50 + false + + + + Channel 0 is 430 MHz, channel 250 is 440 MHz, and the channel spacing is 40 KHz. + + + 250 + + + + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + 440.000 (MHz) + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + @@ -1810,7 +1937,7 @@ Must be selected if Coordinator modem is configured for PPM. - Send settings to the board but do not save to the non-volatile memory + Send settings to the board but do not save to the non-volatile memory. Apply @@ -1820,7 +1947,7 @@ Must be selected if Coordinator modem is configured for PPM. - Send settings to the board and save to the non-volatile memory + Send settings to the board and save to the non-volatile memory. Save From a0d4d811b841db015bfedf4572fc925052210ef2 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Mon, 2 May 2016 03:42:10 +0200 Subject: [PATCH 40/58] LP-302 Vehicle tab - Multirotor: Change motor numbers to motor position --- .../src/plugins/config/airframe_multirotor.ui | 104 +- .../configmultirotorwidget.cpp | 54 + .../cfg_vehicletypes/configmultirotorwidget.h | 1 + .../config/images/multirotor-shapes.svg | 2068 +++++++++++------ 4 files changed, 1534 insertions(+), 693 deletions(-) diff --git a/ground/gcs/src/plugins/config/airframe_multirotor.ui b/ground/gcs/src/plugins/config/airframe_multirotor.ui index 3d46b693a..a50cc8969 100644 --- a/ground/gcs/src/plugins/config/airframe_multirotor.ui +++ b/ground/gcs/src/plugins/config/airframe_multirotor.ui @@ -861,7 +861,16 @@ margin:1px; 6 - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -870,7 +879,7 @@ font: bold 12px; margin:1px; - 5 + Pos5 @@ -891,7 +900,16 @@ margin:1px; - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -900,7 +918,7 @@ font: bold 12px; margin:1px; - 6 + Pos6 @@ -921,7 +939,16 @@ margin:1px; - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -930,7 +957,7 @@ font: bold 12px; margin:1px; - 7 + Pos7 @@ -951,7 +978,16 @@ margin:1px; - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -960,7 +996,7 @@ font: bold 12px; margin:1px; - 8 + Pos8 @@ -1029,7 +1065,16 @@ margin:1px; 6 - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -1038,7 +1083,7 @@ font: bold 12px; margin:1px; - 1 + Pos1 @@ -1056,7 +1101,16 @@ margin:1px; - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -1065,7 +1119,7 @@ font: bold 12px; margin:1px; - 2 + Pos2 @@ -1083,7 +1137,16 @@ margin:1px; - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -1092,7 +1155,7 @@ font: bold 12px; margin:1px; - 3 + Pos3 @@ -1110,7 +1173,16 @@ margin:1px; - + + + + 80 + 0 + + + + Qt::AlignCenter + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -1119,7 +1191,7 @@ font: bold 12px; margin:1px; - 4 + Pos4 diff --git a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 8a31ed61d..3a703070b 100644 --- a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -190,15 +190,21 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) Q_ASSERT(m_aircraft); Q_ASSERT(quad); + QList motorLabels; + if (frameType == "Tri" || frameType == "Tricopter Y") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); + motorLabels << "NW" << "NE" << "S"; + m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); setYawMixLevel(100); } else if (frameType == "QuadX" || frameType == "Quad X") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); + motorLabels << "NW" << "NE" << "SE" << "SW"; + // init mixer levels m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); @@ -206,12 +212,16 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) } else if (frameType == "QuadP" || frameType == "Quad +") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); + motorLabels << "N" << "E" << "S" << "W"; + m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); setYawMixLevel(50); } else if (frameType == "Hexa" || frameType == "Hexacopter") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); + motorLabels << "N" << "NE" << "SE" << "S" << "SW" << "NW"; + m_aircraft->mrRollMixLevel->setValue(100); // Old Roll 50 - Pitch 33 - Yaw 33 m_aircraft->mrPitchMixLevel->setValue(100); // Do not alter mixer matrix setYawMixLevel(100); @@ -219,6 +229,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X")); + motorLabels << "NE" << "E" << "SE" << "SW" << "W" << "NW"; + m_aircraft->mrRollMixLevel->setValue(100); // Old: Roll 33 - Pitch 50 - Yaw 33 m_aircraft->mrPitchMixLevel->setValue(100); // Do not alter mixer matrix setYawMixLevel(100); @@ -226,6 +238,8 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter H")); + motorLabels << "NE" << "E" << "SE" << "SW" << "W" << "NW"; + m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100% setYawMixLevel(100); @@ -233,18 +247,24 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); + motorLabels << "NW Top" << "NW Bottom" << "NE Top" << "NE Bottom" << "S Top" << "S Bottom"; + m_aircraft->mrRollMixLevel->setValue(86); m_aircraft->mrPitchMixLevel->setValue(100); setYawMixLevel(100); } else if (frameType == "Octo" || frameType == "Octocopter") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); + motorLabels << "N" << "NE" << "E" << "SE" << "S" << "SW" << "W" << "NW"; + m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100% setYawMixLevel(100); } else if (frameType == "OctoX" || frameType == "Octocopter X") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter X")); + motorLabels << "NNE" << "ENE" << "ESE" << "SSE" << "SSW" << "WSW" << "WNW" << "NNW"; + m_aircraft->mrRollMixLevel->setValue(100); // Do not alter mixer matrix m_aircraft->mrPitchMixLevel->setValue(100); // All mixers RPY levels = 100% setYawMixLevel(100); @@ -252,18 +272,25 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V")); + motorLabels << "N" << "NE" << "E" << "SE" << "S" << "SW" << "W" << "NW"; + m_aircraft->mrRollMixLevel->setValue(25); m_aircraft->mrPitchMixLevel->setValue(25); setYawMixLevel(25); } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); + motorLabels << "N Top" << "N Bottom" << "E Top" << "E Bottom" << "S Top" << "S Bottom" << "W Top" << "W Bottom"; + m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); setYawMixLevel(50); } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); + motorLabels << "NW Top" << "NW Bottom" << "NE Top" << "NE Bottom" << "SE Top" << "SE Bottom" << "SW Top" << "SW Bottom"; + + m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); setYawMixLevel(50); @@ -272,6 +299,9 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) // Enable/Disable controls setupEnabledControls(frameType); + // Update motor position labels + updateMotorsPositionLabels(motorLabels); + // Draw the appropriate airframe updateAirframe(frameType); } @@ -527,6 +557,30 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) updateAirframe(frameType); } +/** + Helper function to update the UI MotorPositionLabels text + */ +void ConfigMultiRotorWidget::updateMotorsPositionLabels(QList motorLabels) +{ + QList mpList; + mpList << m_aircraft->motorPositionLabel1 << m_aircraft->motorPositionLabel2 + << m_aircraft->motorPositionLabel3 << m_aircraft->motorPositionLabel4 + << m_aircraft->motorPositionLabel5 << m_aircraft->motorPositionLabel6 + << m_aircraft->motorPositionLabel7 << m_aircraft->motorPositionLabel8; + + if (motorLabels.count() < 8) { + int motorCount = motorLabels.count(); + // Fill labels for unused motors + for (int index = motorCount; index < mpList.count(); index++) { + motorLabels.insert(index, "Not used"); + } + } + + foreach(QString posLabel, motorLabels) { + mpList.takeFirst()->setText(posLabel); + } +} + /** Helper function to update the UI widget objects */ diff --git a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h index dc8f1cf3a..7336ef294 100644 --- a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h +++ b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -79,6 +79,7 @@ private: void setYawMixLevel(int); void updateRcCurvesUsed(); void updateAirframe(QString multiRotorType); + void updateMotorsPositionLabels(QList motorLabels); void setupEnabledControls(QString multiRotorType); private slots: diff --git a/ground/gcs/src/plugins/config/images/multirotor-shapes.svg b/ground/gcs/src/plugins/config/images/multirotor-shapes.svg index f59eb0311..88e79e928 100644 --- a/ground/gcs/src/plugins/config/images/multirotor-shapes.svg +++ b/ground/gcs/src/plugins/config/images/multirotor-shapes.svg @@ -25,17 +25,17 @@ guidetolerance="10" inkscape:pageopacity="0" inkscape:pageshadow="2" - inkscape:window-width="1280" - inkscape:window-height="928" + inkscape:window-width="1112" + inkscape:window-height="746" id="namedview6635" showgrid="false" - inkscape:zoom="0.16679771" - inkscape:cx="2344.2732" - inkscape:cy="2636.8234" - inkscape:window-x="0" + inkscape:zoom="0.66883113" + inkscape:cx="592.0899" + inkscape:cy="1972.8034" + inkscape:window-x="751" inkscape:window-y="27" - inkscape:window-maximized="1" - inkscape:current-layer="hexa-coax_reverse" + inkscape:window-maximized="0" + inkscape:current-layer="svg4183" inkscape:object-paths="true" inkscape:snap-midpoints="true" inkscape:snap-global="true" @@ -10049,34 +10049,18 @@ id="path5389" d="m 934.1211,1284.0758 c 9.404,9.413 9.404,24.67 -0.008,34.077 -9.406,9.41 -24.664,9.41 -34.076,0 -9.404,-9.407 -9.404,-24.662 0.008,-34.069 9.406,-9.412 24.664,-9.413 34.076,-0.01" />N +NE +SE +S +SW +NW +W +NE +SE +E +SW +NW +N +S +NW +NE +W +NE +SE +E +SW +NW +N +S +NE +W +NE +SE +E +SW +NW +NNE +ENE +ESE +SSE +SSW +WSW +WNW +NNW +SE +S +ENE + + \ No newline at end of file + d="M 1001.67,1438.583 L 1004.365,1438.583 L 1004.365,1421.855 L 1021.094,1421.855 L 1021.094,1438.583 L 1024.082,1438.583 L 1012.877,1449.788 L 1001.67,1438.583 z" /> \ No newline at end of file From 32a6de6b79e7d34c14351a30fecfb13c2b265ab1 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 1 May 2016 02:04:01 +0200 Subject: [PATCH 41/58] LP-233 Support OneShot42 --- flight/modules/Actuator/actuator.c | 10 ++++++++++ .../targets/boards/coptercontrol/firmware/pios_board.c | 6 ++++-- flight/targets/boards/revonano/firmware/pios_board.c | 3 ++- shared/uavobjectdefinition/actuatorsettings.xml | 2 +- 4 files changed, 17 insertions(+), 4 deletions(-) diff --git a/flight/modules/Actuator/actuator.c b/flight/modules/Actuator/actuator.c index f3f77ca41..7276e27ef 100644 --- a/flight/modules/Actuator/actuator.c +++ b/flight/modules/Actuator/actuator.c @@ -77,6 +77,8 @@ static int8_t counter; #define ACTUATOR_ONESHOT125_CLOCK 2000000 #define ACTUATOR_ONESHOT125_PULSE_SCALE 4 +#define ACTUATOR_ONESHOT42_CLOCK 6000000 +#define ACTUATOR_ONESHOT42_PULSE_SCALE 4 #define ACTUATOR_PWM_CLOCK 1000000 // Private types @@ -941,6 +943,10 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) // Remap 1000-2000 range to 125-250 PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value / ACTUATOR_ONESHOT125_PULSE_SCALE); break; + case ACTUATORSETTINGS_BANKMODE_ONESHOT42: + // Remap 1000-2000 range to 41,666-83,333µs + PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value / ACTUATOR_ONESHOT42_PULSE_SCALE); + break; default: PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value); break; @@ -994,6 +1000,10 @@ static void actuator_update_rate_if_changed(bool force_update) freq[i] = 100; // Value must be small enough so CCr isn't update until the PIOS_Servo_Update is triggered clock[i] = ACTUATOR_ONESHOT125_CLOCK; // Setup an 2MHz timer clock break; + case ACTUATORSETTINGS_BANKMODE_ONESHOT42: + freq[i] = 100; + clock[i] = ACTUATOR_ONESHOT42_CLOCK; + break; case ACTUATORSETTINGS_BANKMODE_PWMSYNC: freq[i] = 100; clock[i] = ACTUATOR_PWM_CLOCK; diff --git a/flight/targets/boards/coptercontrol/firmware/pios_board.c b/flight/targets/boards/coptercontrol/firmware/pios_board.c index 90cbfa8b9..5145ca3da 100644 --- a/flight/targets/boards/coptercontrol/firmware/pios_board.c +++ b/flight/targets/boards/coptercontrol/firmware/pios_board.c @@ -954,7 +954,8 @@ SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook() if ((recmode == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT || flexiMode == HWSETTINGS_CC_FLEXIPORT_PPM) && (modes[3] == ACTUATORSETTINGS_BANKMODE_PWMSYNC || - modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT125)) { + modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 || + modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT42)) { return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT; } else { return SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE; @@ -967,7 +968,8 @@ SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook() case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT: for (uint8_t i = 0; i < ACTUATORSETTINGS_BANKMODE_NUMELEM; i++) { if (modes[i] == ACTUATORSETTINGS_BANKMODE_PWMSYNC || - modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125) { + modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 || + modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT42) { return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;; } diff --git a/flight/targets/boards/revonano/firmware/pios_board.c b/flight/targets/boards/revonano/firmware/pios_board.c index 4cc6f58d9..c3f42ad0e 100644 --- a/flight/targets/boards/revonano/firmware/pios_board.c +++ b/flight/targets/boards/revonano/firmware/pios_board.c @@ -893,7 +893,8 @@ SystemAlarmsExtendedAlarmStatusOptions RevoNanoConfigHook() case HWSETTINGS_RM_RCVRPORT_PWM: for (uint8_t i = 0; i < ACTUATORSETTINGS_BANKMODE_NUMELEM; i++) { if (modes[i] == ACTUATORSETTINGS_BANKMODE_PWMSYNC || - modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125) { + modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 || + modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT42) { return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;; } } diff --git a/shared/uavobjectdefinition/actuatorsettings.xml b/shared/uavobjectdefinition/actuatorsettings.xml index 4890a0c60..e57633f67 100644 --- a/shared/uavobjectdefinition/actuatorsettings.xml +++ b/shared/uavobjectdefinition/actuatorsettings.xml @@ -2,7 +2,7 @@ Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - + From 49107e40079a9e6eac1ba6a09f4ab8ab130d9136 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 1 May 2016 14:10:49 +0200 Subject: [PATCH 42/58] LP-233 Increase Oneshot output resolution --- flight/modules/Actuator/actuator.c | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/flight/modules/Actuator/actuator.c b/flight/modules/Actuator/actuator.c index 7276e27ef..b661d5d30 100644 --- a/flight/modules/Actuator/actuator.c +++ b/flight/modules/Actuator/actuator.c @@ -61,25 +61,25 @@ static int8_t counter; #endif // Private constants -#define MAX_QUEUE_SIZE 2 +#define MAX_QUEUE_SIZE 2 #if defined(PIOS_ACTUATOR_STACK_SIZE) -#define STACK_SIZE_BYTES PIOS_ACTUATOR_STACK_SIZE +#define STACK_SIZE_BYTES PIOS_ACTUATOR_STACK_SIZE #else -#define STACK_SIZE_BYTES 1312 +#define STACK_SIZE_BYTES 1312 #endif -#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) // device driver -#define FAILSAFE_TIMEOUT_MS 100 -#define MAX_MIX_ACTUATORS ACTUATORCOMMAND_CHANNEL_NUMELEM +#define TASK_PRIORITY (tskIDLE_PRIORITY + 4) // device driver +#define FAILSAFE_TIMEOUT_MS 100 +#define MAX_MIX_ACTUATORS ACTUATORCOMMAND_CHANNEL_NUMELEM -#define CAMERA_BOOT_DELAY_MS 7000 +#define CAMERA_BOOT_DELAY_MS 7000 -#define ACTUATOR_ONESHOT125_CLOCK 2000000 -#define ACTUATOR_ONESHOT125_PULSE_SCALE 4 -#define ACTUATOR_ONESHOT42_CLOCK 6000000 -#define ACTUATOR_ONESHOT42_PULSE_SCALE 4 -#define ACTUATOR_PWM_CLOCK 1000000 +#define ACTUATOR_ONESHOT125_CLOCK 12000000 +#define ACTUATOR_ONESHOT125_PULSE_FACTOR 1.5f +#define ACTUATOR_ONESHOT42_CLOCK 12000000 +#define ACTUATOR_ONESHOT42_PULSE_SCALE 2 +#define ACTUATOR_PWM_CLOCK 1000000 // Private types @@ -941,7 +941,7 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) switch (mode) { case ACTUATORSETTINGS_BANKMODE_ONESHOT125: // Remap 1000-2000 range to 125-250 - PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value / ACTUATOR_ONESHOT125_PULSE_SCALE); + PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value * ACTUATOR_ONESHOT125_PULSE_FACTOR); break; case ACTUATORSETTINGS_BANKMODE_ONESHOT42: // Remap 1000-2000 range to 41,666-83,333µs @@ -998,11 +998,11 @@ static void actuator_update_rate_if_changed(bool force_update) switch (actuatorSettings.BankMode[i]) { case ACTUATORSETTINGS_BANKMODE_ONESHOT125: freq[i] = 100; // Value must be small enough so CCr isn't update until the PIOS_Servo_Update is triggered - clock[i] = ACTUATOR_ONESHOT125_CLOCK; // Setup an 2MHz timer clock + clock[i] = ACTUATOR_ONESHOT125_CLOCK; // Setup an 12MHz timer clock break; case ACTUATORSETTINGS_BANKMODE_ONESHOT42: freq[i] = 100; - clock[i] = ACTUATOR_ONESHOT42_CLOCK; + clock[i] = ACTUATOR_ONESHOT42_CLOCK; // Setup an 12MHz timer clock break; case ACTUATORSETTINGS_BANKMODE_PWMSYNC: freq[i] = 100; From 78be10ff28485a12a4bad14675c667f826802266 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 1 May 2016 18:28:37 +0200 Subject: [PATCH 43/58] LP-233 Multiply / factor instead of scale --- flight/modules/Actuator/actuator.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/modules/Actuator/actuator.c b/flight/modules/Actuator/actuator.c index b661d5d30..df89a8ed4 100644 --- a/flight/modules/Actuator/actuator.c +++ b/flight/modules/Actuator/actuator.c @@ -78,7 +78,7 @@ static int8_t counter; #define ACTUATOR_ONESHOT125_CLOCK 12000000 #define ACTUATOR_ONESHOT125_PULSE_FACTOR 1.5f #define ACTUATOR_ONESHOT42_CLOCK 12000000 -#define ACTUATOR_ONESHOT42_PULSE_SCALE 2 +#define ACTUATOR_ONESHOT42_PULSE_FACTOR 0.5f #define ACTUATOR_PWM_CLOCK 1000000 // Private types @@ -940,12 +940,12 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) uint8_t mode = pinsMode[actuatorSettings.ChannelAddr[mixer_channel]]; switch (mode) { case ACTUATORSETTINGS_BANKMODE_ONESHOT125: - // Remap 1000-2000 range to 125-250 + // Remap 1000-2000 range to 125-250µs PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value * ACTUATOR_ONESHOT125_PULSE_FACTOR); break; case ACTUATORSETTINGS_BANKMODE_ONESHOT42: // Remap 1000-2000 range to 41,666-83,333µs - PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value / ACTUATOR_ONESHOT42_PULSE_SCALE); + PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value * ACTUATOR_ONESHOT42_PULSE_FACTOR); break; default: PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value); From 2bda2e2901506191cf06ea95058baa698eb15955 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 1 May 2016 19:24:41 +0200 Subject: [PATCH 44/58] LP-233 Simplify, same clock used for all OneShot modes --- flight/modules/Actuator/actuator.c | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/flight/modules/Actuator/actuator.c b/flight/modules/Actuator/actuator.c index df89a8ed4..d9cc780eb 100644 --- a/flight/modules/Actuator/actuator.c +++ b/flight/modules/Actuator/actuator.c @@ -75,9 +75,8 @@ static int8_t counter; #define CAMERA_BOOT_DELAY_MS 7000 -#define ACTUATOR_ONESHOT125_CLOCK 12000000 +#define ACTUATOR_ONESHOT_CLOCK 12000000 #define ACTUATOR_ONESHOT125_PULSE_FACTOR 1.5f -#define ACTUATOR_ONESHOT42_CLOCK 12000000 #define ACTUATOR_ONESHOT42_PULSE_FACTOR 0.5f #define ACTUATOR_PWM_CLOCK 1000000 // Private types @@ -997,12 +996,9 @@ static void actuator_update_rate_if_changed(bool force_update) } switch (actuatorSettings.BankMode[i]) { case ACTUATORSETTINGS_BANKMODE_ONESHOT125: - freq[i] = 100; // Value must be small enough so CCr isn't update until the PIOS_Servo_Update is triggered - clock[i] = ACTUATOR_ONESHOT125_CLOCK; // Setup an 12MHz timer clock - break; case ACTUATORSETTINGS_BANKMODE_ONESHOT42: - freq[i] = 100; - clock[i] = ACTUATOR_ONESHOT42_CLOCK; // Setup an 12MHz timer clock + freq[i] = 100; // Value must be small enough so CCr isn't update until the PIOS_Servo_Update is triggered + clock[i] = ACTUATOR_ONESHOT_CLOCK; // Setup an 12MHz timer clock break; case ACTUATORSETTINGS_BANKMODE_PWMSYNC: freq[i] = 100; From 214ae849a2ec8c5a729e6e001aeb9b094f5999d7 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Mon, 2 May 2016 20:22:05 +0200 Subject: [PATCH 45/58] =?UTF-8?q?LP-233=20Add=20MultiShot=205=20-=2025?= =?UTF-8?q?=C2=B5s=20pulses?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- flight/modules/Actuator/actuator.c | 6 ++++++ flight/targets/boards/coptercontrol/firmware/pios_board.c | 6 ++++-- flight/targets/boards/revonano/firmware/pios_board.c | 3 ++- shared/uavobjectdefinition/actuatorsettings.xml | 2 +- 4 files changed, 13 insertions(+), 4 deletions(-) diff --git a/flight/modules/Actuator/actuator.c b/flight/modules/Actuator/actuator.c index d9cc780eb..a2a66838f 100644 --- a/flight/modules/Actuator/actuator.c +++ b/flight/modules/Actuator/actuator.c @@ -78,6 +78,7 @@ static int8_t counter; #define ACTUATOR_ONESHOT_CLOCK 12000000 #define ACTUATOR_ONESHOT125_PULSE_FACTOR 1.5f #define ACTUATOR_ONESHOT42_PULSE_FACTOR 0.5f +#define ACTUATOR_MULTISHOT_PULSE_FACTOR 0.24f #define ACTUATOR_PWM_CLOCK 1000000 // Private types @@ -946,6 +947,10 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) // Remap 1000-2000 range to 41,666-83,333µs PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value * ACTUATOR_ONESHOT42_PULSE_FACTOR); break; + case ACTUATORSETTINGS_BANKMODE_MULTISHOT: + // Remap 1000-2000 range to 5-25µs + PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], (value * ACTUATOR_MULTISHOT_PULSE_FACTOR) - 180); + break; default: PIOS_Servo_Set(actuatorSettings.ChannelAddr[mixer_channel], value); break; @@ -997,6 +1002,7 @@ static void actuator_update_rate_if_changed(bool force_update) switch (actuatorSettings.BankMode[i]) { case ACTUATORSETTINGS_BANKMODE_ONESHOT125: case ACTUATORSETTINGS_BANKMODE_ONESHOT42: + case ACTUATORSETTINGS_BANKMODE_MULTISHOT: freq[i] = 100; // Value must be small enough so CCr isn't update until the PIOS_Servo_Update is triggered clock[i] = ACTUATOR_ONESHOT_CLOCK; // Setup an 12MHz timer clock break; diff --git a/flight/targets/boards/coptercontrol/firmware/pios_board.c b/flight/targets/boards/coptercontrol/firmware/pios_board.c index 5145ca3da..8ba03f975 100644 --- a/flight/targets/boards/coptercontrol/firmware/pios_board.c +++ b/flight/targets/boards/coptercontrol/firmware/pios_board.c @@ -955,7 +955,8 @@ SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook() flexiMode == HWSETTINGS_CC_FLEXIPORT_PPM) && (modes[3] == ACTUATORSETTINGS_BANKMODE_PWMSYNC || modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 || - modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT42)) { + modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT42 || + modes[3] == ACTUATORSETTINGS_BANKMODE_MULTISHOT)) { return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT; } else { return SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE; @@ -969,7 +970,8 @@ SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook() for (uint8_t i = 0; i < ACTUATORSETTINGS_BANKMODE_NUMELEM; i++) { if (modes[i] == ACTUATORSETTINGS_BANKMODE_PWMSYNC || modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 || - modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT42) { + modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT42 || + modes[i] == ACTUATORSETTINGS_BANKMODE_MULTISHOT) { return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;; } diff --git a/flight/targets/boards/revonano/firmware/pios_board.c b/flight/targets/boards/revonano/firmware/pios_board.c index c3f42ad0e..f02a2fdbf 100644 --- a/flight/targets/boards/revonano/firmware/pios_board.c +++ b/flight/targets/boards/revonano/firmware/pios_board.c @@ -894,7 +894,8 @@ SystemAlarmsExtendedAlarmStatusOptions RevoNanoConfigHook() for (uint8_t i = 0; i < ACTUATORSETTINGS_BANKMODE_NUMELEM; i++) { if (modes[i] == ACTUATORSETTINGS_BANKMODE_PWMSYNC || modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 || - modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT42) { + modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT42 || + modes[i] == ACTUATORSETTINGS_BANKMODE_MULTISHOT) { return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;; } } diff --git a/shared/uavobjectdefinition/actuatorsettings.xml b/shared/uavobjectdefinition/actuatorsettings.xml index e57633f67..6aaed72f7 100644 --- a/shared/uavobjectdefinition/actuatorsettings.xml +++ b/shared/uavobjectdefinition/actuatorsettings.xml @@ -2,7 +2,7 @@ Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - + From bf639b486d006088ba98b441ef14ee44221644ef Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 3 May 2016 00:06:24 +0200 Subject: [PATCH 46/58] LP-304 - declare counters as static --- flight/pios/inc/pios_instrumentation_helper.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/flight/pios/inc/pios_instrumentation_helper.h b/flight/pios/inc/pios_instrumentation_helper.h index 819a88aaa..2fffbdf4b 100644 --- a/flight/pios/inc/pios_instrumentation_helper.h +++ b/flight/pios/inc/pios_instrumentation_helper.h @@ -2,7 +2,8 @@ ****************************************************************************** * * @file pios_instrumentation_helper.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @author The LibrePilot Project, http://www.librepilot.org, Copyright (c) 2016 + * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. * @brief Macros to easily add optional performance monitoring to a module * * @see The GNU Public License (GPL) Version 3 @@ -84,7 +85,7 @@ /** * include the following macro together with modules variable declaration */ -#define PERF_DEFINE_COUNTER(x) pios_counter_t x +#define PERF_DEFINE_COUNTER(x) static pios_counter_t x /** * this mast be called at some module init code From 1b254e41824c379a9b9eeb01b327f4f0737246cb Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 3 May 2016 00:07:10 +0200 Subject: [PATCH 47/58] LP-304 - Prevent errors when dealing with variables used only for instrumentation --- flight/pios/inc/pios_instrumentation_helper.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/pios/inc/pios_instrumentation_helper.h b/flight/pios/inc/pios_instrumentation_helper.h index 2fffbdf4b..6a9423a66 100644 --- a/flight/pios/inc/pios_instrumentation_helper.h +++ b/flight/pios/inc/pios_instrumentation_helper.h @@ -109,7 +109,7 @@ #define PERF_TIMED_SECTION_START(x) #define PERF_TIMED_SECTION_END(x) #define PERF_MEASURE_PERIOD(x) -#define PERF_TRACK_VALUE(x, y) +#define PERF_TRACK_VALUE(x, y) (void)y #define PERF_INCREMENT_VALUE(x) #define PERF_DECREMENT_VALUE(x) #endif /* PIOS_INCLUDE_INSTRUMENTATION */ From 5156c0c9111990e106d7e7e1849df3dd6fa8bcf2 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 3 May 2016 00:07:35 +0200 Subject: [PATCH 48/58] LP-304 - Allow further info to be added to PERF_INIT_COUNTER for future feature support. This may allow in future to extract the counters id list with grep to be handled by gcs or other custom tools Proposed usage: PERF_INIT_COUNTER(counterVariable, id, "MODULE NAME","COUNTER DESCRIPTION","UNIT OF MEASURE"); i.e.: PERF_INIT_COUNTER(counterExecutionTime, 0xAC700001, "ACTUATOR", "Actuator update execution time", "uS"); --- flight/pios/inc/pios_instrumentation_helper.h | 32 +++++++++++-------- 1 file changed, 19 insertions(+), 13 deletions(-) diff --git a/flight/pios/inc/pios_instrumentation_helper.h b/flight/pios/inc/pios_instrumentation_helper.h index 6a9423a66..277f183fe 100644 --- a/flight/pios/inc/pios_instrumentation_helper.h +++ b/flight/pios/inc/pios_instrumentation_helper.h @@ -52,10 +52,16 @@ * The following code needs to be added to a function called at module initialization. * the second parameter is a unique counter Id. * A good pracice is to use the upper half word as module id and lower as counter id - *
PERF_INIT_COUNTER(counterUpd, 0xA7710001);
- * PERF_INIT_COUNTER(counterAtt, 0xA7710002);
- * PERF_INIT_COUNTER(counterPeriod, 0xA7710003);
- * PERF_INIT_COUNTER(counterAccelSamples, 0xA7710004);
+ * Optionally three strings containing Module Name, Counter description and unit of measure can be passed. + * Those strings will be used in future to automatically extract the list of counters from code to managed + * by GCS or some other custom tool. + * + * PERF_INIT_COUNTER(counterVariable, id, "MODULE NAME","COUNTER DESCRIPTION","UNIT OF MEASURE"); + * + *
PERF_INIT_COUNTER(counterUpd, 0xA7710001, "ATTITUDE", "Sensor update execution time", "us");
+ * PERF_INIT_COUNTER(counterAtt, 0xA7710002, "ATTITUDE", "Attitude estimation execution time", "us");
+ * PERF_INIT_COUNTER(counterPeriod, 0xA7710003, "ATTITUDE", "Sensor update period", "us");
+ * PERF_INIT_COUNTER(counterAccelSamples, 0xA7710004, "ATTITUDE", "Samples for each sensor cycle", "count");
* * At this point you can start using the counters as in the following samples * @@ -85,27 +91,27 @@ /** * include the following macro together with modules variable declaration */ -#define PERF_DEFINE_COUNTER(x) static pios_counter_t x +#define PERF_DEFINE_COUNTER(x) static pios_counter_t x /** * this mast be called at some module init code */ -#define PERF_INIT_COUNTER(x, id) x = PIOS_Instrumentation_CreateCounter(id) +#define PERF_INIT_COUNTER(x, id, ...) x = PIOS_Instrumentation_CreateCounter(id) /** * those are the monitoring macros */ -#define PERF_TIMED_SECTION_START(x) PIOS_Instrumentation_TimeStart(x) -#define PERF_TIMED_SECTION_END(x) PIOS_Instrumentation_TimeEnd(x) -#define PERF_MEASURE_PERIOD(x) PIOS_Instrumentation_TrackPeriod(x) -#define PERF_TRACK_VALUE(x, y) PIOS_Instrumentation_updateCounter(x, y) -#define PERF_INCREMENT_VALUE(x) PIOS_Instrumentation_incrementCounter(x, 1) -#define PERF_DECREMENT_VALUE(x) PIOS_Instrumentation_incrementCounter(x, -1) +#define PERF_TIMED_SECTION_START(x) PIOS_Instrumentation_TimeStart(x) +#define PERF_TIMED_SECTION_END(x) PIOS_Instrumentation_TimeEnd(x) +#define PERF_MEASURE_PERIOD(x) PIOS_Instrumentation_TrackPeriod(x) +#define PERF_TRACK_VALUE(x, y) PIOS_Instrumentation_updateCounter(x, y) +#define PERF_INCREMENT_VALUE(x) PIOS_Instrumentation_incrementCounter(x, 1) +#define PERF_DECREMENT_VALUE(x) PIOS_Instrumentation_incrementCounter(x, -1) #else #define PERF_DEFINE_COUNTER(x) -#define PERF_INIT_COUNTER(x, id) +#define PERF_INIT_COUNTER(x, id, ...) #define PERF_TIMED_SECTION_START(x) #define PERF_TIMED_SECTION_END(x) #define PERF_MEASURE_PERIOD(x) From 6bd6ef5be18fb01908232ca2d7b2b65171fa0f55 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 3 May 2016 01:00:06 +0200 Subject: [PATCH 49/58] LP-150 - Run attitude estimation at a configurable fraction of gyro sample rate for CC/CC3D --- flight/modules/Attitude/attitude.c | 49 ++++++++++++++----- .../coptercontrol/firmware/inc/pios_config.h | 3 +- 2 files changed, 39 insertions(+), 13 deletions(-) diff --git a/flight/modules/Attitude/attitude.c b/flight/modules/Attitude/attitude.c index f2d024d24..98d903f3b 100644 --- a/flight/modules/Attitude/attitude.c +++ b/flight/modules/Attitude/attitude.c @@ -332,11 +332,8 @@ static void AttitudeTask(__attribute__((unused)) void *parameters) } else { // Do not update attitude data in simulation mode if (!AttitudeStateReadOnly()) { - PERF_TIMED_SECTION_START(counterAtt); updateAttitude(&accelState, &gyros); - PERF_TIMED_SECTION_END(counterAtt); } - PERF_MEASURE_PERIOD(counterPeriod); AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); } vTaskDelayUntil(&lastSysTime, sensor_period_ms / portTICK_PERIOD_MS); @@ -606,17 +603,41 @@ static inline void apply_accel_filter(const float *raw, float *filtered) __attribute__((optimize("O3"))) static void updateAttitude(AccelStateData *accelStateData, GyroStateData *gyrosData) { - float dT = PIOS_DELTATIME_GetAverageSeconds(&dtconfig); + static uint32_t samples = 0; + static float gyros_accum[3]; + static float accels_accum[3]; + // Bad practice to assume structure order, but saves memory float *gyros = &gyrosData->x; float *accels = &accelStateData->x; + if (samples < ATTITUDE_SENSORS_DOWNSAMPLE - 1) { + gyros_accum[0] += gyros[0]; + gyros_accum[1] += gyros[1]; + gyros_accum[2] += gyros[2]; + accels_accum[0] += accels[0]; + accels_accum[1] += accels[1]; + accels_accum[2] += accels[2]; + samples++; + return; + } + float dT = PIOS_DELTATIME_GetAverageSeconds(&dtconfig); + PERF_TIMED_SECTION_START(counterAtt); + float inv_samples_count = 1.0f / (float)samples; + samples = 0; + gyros_accum[0] *= inv_samples_count; + gyros_accum[1] *= inv_samples_count; + gyros_accum[2] *= inv_samples_count; + accels_accum[0] *= inv_samples_count; + accels_accum[1] *= inv_samples_count; + accels_accum[2] *= inv_samples_count; + float grot[3]; float accel_err[3]; // Apply smoothing to accel values, to reduce vibration noise before main calculations. - apply_accel_filter(accels, accels_filtered); + apply_accel_filter(accels_accum, accels_filtered); // Rotate gravity unit vector to body frame, filter and cross with accels grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2])); @@ -658,18 +679,18 @@ __attribute__((optimize("O3"))) static void updateAttitude(AccelStateData *accel // Correct rates based on error, integral component dealt with in updateSensors const float kpInvdT = accelKp / dT; - gyros[0] += accel_err[0] * kpInvdT; - gyros[1] += accel_err[1] * kpInvdT; - gyros[2] += accel_err[2] * kpInvdT; + gyros_accum[0] += accel_err[0] * kpInvdT; + gyros_accum[1] += accel_err[1] * kpInvdT; + gyros_accum[2] += accel_err[2] * kpInvdT; { // scoping variables to save memory // Work out time derivative from INSAlgo writeup // Also accounts for the fact that gyros are in deg/s float qdot[4]; - qdot[0] = (-q[1] * gyros[0] - q[2] * gyros[1] - q[3] * gyros[2]) * dT * (M_PI_F / 180.0f / 2.0f); - qdot[1] = (q[0] * gyros[0] - q[3] * gyros[1] + q[2] * gyros[2]) * dT * (M_PI_F / 180.0f / 2.0f); - qdot[2] = (q[3] * gyros[0] + q[0] * gyros[1] - q[1] * gyros[2]) * dT * (M_PI_F / 180.0f / 2.0f); - qdot[3] = (-q[2] * gyros[0] + q[1] * gyros[1] + q[0] * gyros[2]) * dT * (M_PI_F / 180.0f / 2.0f); + qdot[0] = (-q[1] * gyros_accum[0] - q[2] * gyros_accum[1] - q[3] * gyros_accum[2]) * dT * (M_PI_F / 180.0f / 2.0f); + qdot[1] = (q[0] * gyros_accum[0] - q[3] * gyros_accum[1] + q[2] * gyros_accum[2]) * dT * (M_PI_F / 180.0f / 2.0f); + qdot[2] = (q[3] * gyros_accum[0] + q[0] * gyros_accum[1] - q[1] * gyros_accum[2]) * dT * (M_PI_F / 180.0f / 2.0f); + qdot[3] = (-q[2] * gyros_accum[0] + q[1] * gyros_accum[1] + q[0] * gyros_accum[2]) * dT * (M_PI_F / 180.0f / 2.0f); // Take a time step q[0] = q[0] + qdot[0]; @@ -711,6 +732,10 @@ __attribute__((optimize("O3"))) static void updateAttitude(AccelStateData *accel Quaternion2RPY(&attitudeState.q1, &attitudeState.Roll); AttitudeStateSet(&attitudeState); + gyros_accum[0] = gyros_accum[1] = gyros_accum[2] = 0.0f; + accels_accum[0] = accels_accum[1] = accels_accum[2] = 0.0f; + PERF_TIMED_SECTION_END(counterAtt); + PERF_MEASURE_PERIOD(counterPeriod); } static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv) diff --git a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h index b207bd0c2..122b0fcc8 100644 --- a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h +++ b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h @@ -93,7 +93,8 @@ /* #define PIOS_INCLUDE_ETASV3 */ /* #define PIOS_INCLUDE_HCSR04 */ -#define PIOS_SENSOR_RATE 500.0f +#define PIOS_SENSOR_RATE 500.0f +#define ATTITUDE_SENSORS_DOWNSAMPLE 4 /* PIOS receiver drivers */ #define PIOS_INCLUDE_PWM From e14e5febe2c67fa0755ef92febf81b6235b86be1 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 3 May 2016 01:00:28 +0200 Subject: [PATCH 50/58] LP-150 - prevent stab error conditions --- flight/modules/Stabilization/inc/stabilization.h | 5 ++++- flight/modules/Stabilization/outerloop.c | 13 +++++++++---- .../boards/coptercontrol/firmware/inc/pios_config.h | 1 + 3 files changed, 14 insertions(+), 5 deletions(-) diff --git a/flight/modules/Stabilization/inc/stabilization.h b/flight/modules/Stabilization/inc/stabilization.h index b1ff2fc13..fbf8dbf9b 100644 --- a/flight/modules/Stabilization/inc/stabilization.h +++ b/flight/modules/Stabilization/inc/stabilization.h @@ -80,9 +80,12 @@ extern StabilizationData stabSettings; // must be same as eventdispatcher to avoid needing additional mutexes #define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL +#ifndef STABILIZATION_ATTITUDE_DOWNSAMPLED // outer loop only executes every 4th uavobject update to save CPU #define OUTERLOOP_SKIPCOUNT 4 - +#else +#define OUTERLOOP_SKIPCOUNT ATTITUDE_SENSORS_DOWNSAMPLE +#endif // STABILIZATION_ATTITUDE_DOWNSAMPLED #endif // STABILIZATION_H /** diff --git a/flight/modules/Stabilization/outerloop.c b/flight/modules/Stabilization/outerloop.c index 31c81e86c..9fc3c6e4a 100644 --- a/flight/modules/Stabilization/outerloop.c +++ b/flight/modules/Stabilization/outerloop.c @@ -365,14 +365,19 @@ static void stabilizationOuterloopTask() static void AttitudeStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { +#ifndef STABILIZATION_ATTITUDE_DOWNSAMPLED // to reduce CPU utilization, outer loop is not executed on every state update static uint8_t cpusaver = 0; if ((cpusaver++ % OUTERLOOP_SKIPCOUNT) == 0) { - // this does not need mutex protection as both eventdispatcher and stabi run in same callback task! - AttitudeStateGet(&attitude); - PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle); - } +#endif + // this does not need mutex protection as both eventdispatcher and stabi run in same callback task! + AttitudeStateGet(&attitude); + PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle); + +#ifndef STABILIZATION_ATTITUDE_DOWNSAMPLED +} +#endif } /** diff --git a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h index 122b0fcc8..6c617d06f 100644 --- a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h +++ b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h @@ -94,6 +94,7 @@ /* #define PIOS_INCLUDE_HCSR04 */ #define PIOS_SENSOR_RATE 500.0f +#define STABILIZATION_ATTITUDE_DOWNSAMPLED #define ATTITUDE_SENSORS_DOWNSAMPLE 4 /* PIOS receiver drivers */ From 1b5dda3ee4b28cae7af0fcc367377717bb0de1aa Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 5 May 2016 13:20:45 +0200 Subject: [PATCH 51/58] LP-302 Small changes: move to QStringList and remove magic numbers. --- .../cfg_vehicletypes/configmultirotorwidget.cpp | 12 +++++++----- .../config/cfg_vehicletypes/configmultirotorwidget.h | 2 +- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 3a703070b..f4177a8c4 100644 --- a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -190,7 +190,7 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) Q_ASSERT(m_aircraft); Q_ASSERT(quad); - QList motorLabels; + QStringList motorLabels; if (frameType == "Tri" || frameType == "Tricopter Y") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); @@ -560,7 +560,7 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) /** Helper function to update the UI MotorPositionLabels text */ -void ConfigMultiRotorWidget::updateMotorsPositionLabels(QList motorLabels) +void ConfigMultiRotorWidget::updateMotorsPositionLabels(QStringList motorLabels) { QList mpList; mpList << m_aircraft->motorPositionLabel1 << m_aircraft->motorPositionLabel2 @@ -568,10 +568,12 @@ void ConfigMultiRotorWidget::updateMotorsPositionLabels(QList motorLabe << m_aircraft->motorPositionLabel5 << m_aircraft->motorPositionLabel6 << m_aircraft->motorPositionLabel7 << m_aircraft->motorPositionLabel8; - if (motorLabels.count() < 8) { - int motorCount = motorLabels.count(); + int motorCount = motorLabels.count(); + int uiLabelsCount = mpList.count(); + + if (motorCount < uiLabelsCount) { // Fill labels for unused motors - for (int index = motorCount; index < mpList.count(); index++) { + for (int index = motorCount; index < uiLabelsCount; index++) { motorLabels.insert(index, "Not used"); } } diff --git a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h index 7336ef294..f38495913 100644 --- a/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h +++ b/ground/gcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -79,7 +79,7 @@ private: void setYawMixLevel(int); void updateRcCurvesUsed(); void updateAirframe(QString multiRotorType); - void updateMotorsPositionLabels(QList motorLabels); + void updateMotorsPositionLabels(QStringList motorLabels); void setupEnabledControls(QString multiRotorType); private slots: From c4c0fc21e31f72cfc1b856fdb747dc95ca726c3b Mon Sep 17 00:00:00 2001 From: James Duley Date: Wed, 27 Apr 2016 21:15:33 +0100 Subject: [PATCH 52/58] Make sure dist tar modification time is consistent --- Makefile | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 21c7b55eb..d6f9049b4 100644 --- a/Makefile +++ b/Makefile @@ -382,12 +382,13 @@ $(DIST_TAR): $(DIST_VER_INFO) .git/index | $(DIST_DIR) @$(ECHO) " SOURCE FOR DISTRIBUTION $(call toprel, $(DIST_TAR))" $(V1) git archive --prefix="$(PACKAGE_NAME)/" -o "$(DIST_TAR)" HEAD $(V1) tar --append --file="$(DIST_TAR)" \ + --owner=root --group=root --mtime="`git show -s --format=%ci`" \ --transform='s,.*version-info.json,$(PACKAGE_NAME)/version-info.json,' \ $(call toprel, "$(DIST_VER_INFO)") $(DIST_TAR_GZ): $(DIST_TAR) @$(ECHO) " SOURCE FOR DISTRIBUTION $(call toprel, $(DIST_TAR_GZ))" - $(V1) gzip -kf "$(DIST_TAR)" + $(V1) gzip -knf "$(DIST_TAR)" .PHONY: dist_tar_gz dist_tar_gz: $(DIST_TAR_GZ) @@ -399,12 +400,13 @@ dist: dist_tar_gz $(FW_DIST_TAR): $(PACKAGE_FW_TARGETS) | $(DIST_DIR) @$(ECHO) " FIRMWARE FOR DISTRIBUTION $(call toprel, $(FW_DIST_TAR))" $(V1) tar -c --file="$(FW_DIST_TAR)" --directory=$(FLIGHT_OUT_DIR) \ + --owner=root --group=root --mtime="`git show -s --format=%ci`" \ --transform='s,^,firmware/,' \ $(foreach fw_targ,$(PACKAGE_FW_TARGETS),$(fw_targ)/$(fw_targ).opfw) $(FW_DIST_TAR_GZ): $(FW_DIST_TAR) @$(ECHO) " FIRMWARE FOR DISTRIBUTION $(call toprel, $(FW_DIST_TAR_GZ))" - $(V1) gzip -kf "$(FW_DIST_TAR)" + $(V1) gzip -knf "$(FW_DIST_TAR)" .PHONY: fw_dist_tar_gz fw_dist_tar_gz: $(FW_DIST_TAR_GZ) From 5be9d022e4aa81a6f8d3821075b5541a69c03c75 Mon Sep 17 00:00:00 2001 From: James Duley Date: Sat, 7 May 2016 10:05:34 +0100 Subject: [PATCH 53/58] Exclude artwork, flight and hardware from source distribution --- .gitattributes | 5 +++++ Makefile | 3 ++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/.gitattributes b/.gitattributes index 9b4c80545..cb13e8da3 100644 --- a/.gitattributes +++ b/.gitattributes @@ -32,3 +32,8 @@ /Makefile text eol=lf # More attributes are defined in per-directory .gitattributes which override this file + +# Not needed in source distribution for building GCS +/artwork/ export-ignore +/flight/ export-ignore +/hardware/ export-ignore diff --git a/Makefile b/Makefile index d6f9049b4..fe2e09e94 100644 --- a/Makefile +++ b/Makefile @@ -235,7 +235,8 @@ endif FLIGHT_OUT_DIR := $(BUILD_DIR)/firmware DIRS += $(FLIGHT_OUT_DIR) -include $(ROOT_DIR)/flight/Makefile +# Might not be here in source package +-include $(ROOT_DIR)/flight/Makefile ############################## # From 3fd0e2e6a7592abdf30b82139a77d5a2201a8d63 Mon Sep 17 00:00:00 2001 From: James Duley Date: Fri, 6 May 2016 22:30:23 +0100 Subject: [PATCH 54/58] Fix up config generation to be safe with spaces --- Makefile | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index fe2e09e94..dde9d8cb3 100644 --- a/Makefile +++ b/Makefile @@ -496,8 +496,10 @@ build-info: | $(BUILD_DIR) # ############################## -CONFIG_OPTS := $(addsuffix \n,$(MAKEOVERRIDES)) -CONFIG_OPTS := $(addprefix override$(SPACE),$(CONFIG_OPTS)) +CONFIG_OPTS := $(subst \$(SPACE),%SPACE_PLACEHOLDER%,$(MAKEOVERRIDES)) +CONFIG_OPTS := $(addprefix override%SPACE_PLACEHOLDER%,$(CONFIG_OPTS)) +CONFIG_OPTS := $(subst $(SPACE),\n,$(CONFIG_OPTS))\n +CONFIG_OPTS := $(subst %SPACE_PLACEHOLDER%,$(SPACE),$(CONFIG_OPTS)) .PHONY: config_new config_new: From 832931f9c557048bdbc8adcabf85713dc30eada5 Mon Sep 17 00:00:00 2001 From: James Duley Date: Fri, 6 May 2016 23:00:39 +0100 Subject: [PATCH 55/58] Add variable to add extra options to dpkg-buildpackage --- package/linux/deb.mk | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/package/linux/deb.mk b/package/linux/deb.mk index a752bfb82..e2f7ec004 100644 --- a/package/linux/deb.mk +++ b/package/linux/deb.mk @@ -37,7 +37,7 @@ package: debian @$(ECHO) "Building Linux package, please wait..." $(V1) sed -i -e "$(PACKAGE_DEPS_SED)" debian/control $(V1) sed -i -e 's,config_new.*, --help > /dev/null,' debian/rules - $(V1) dpkg-buildpackage -b -us -uc -nc + $(V1) dpkg-buildpackage -b -us -uc -nc $(DPKG_BUILDPACKAGE_OPTS) $(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR) $(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR) $(V1) rm -r debian @@ -56,7 +56,7 @@ endif .PHONY: package_src package_src: $(DEB_ORIG_SRC_NAME) $(DEB_PACKAGE_DIR) - $(V1) cd $(DEB_PACKAGE_DIR) && dpkg-buildpackage -S -us -uc + $(V1) cd $(DEB_PACKAGE_DIR) && dpkg-buildpackage -S -us -uc $(DPKG_BUILDPACKAGE_OPTS) $(DEB_ORIG_SRC): $(DIST_TAR_GZ) | $(PACKAGE_DIR) $(V1) cp $(DIST_TAR_GZ) $(DEB_ORIG_SRC) From 19b474341c4e8c27e038aa0f246fe80730fc76b8 Mon Sep 17 00:00:00 2001 From: James Duley Date: Sat, 7 May 2016 10:26:59 +0100 Subject: [PATCH 56/58] Stop extra junk getting in debian dir by explicitly copying files --- package/linux/deb.mk | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/package/linux/deb.mk b/package/linux/deb.mk index e2f7ec004..d30691af6 100644 --- a/package/linux/deb.mk +++ b/package/linux/deb.mk @@ -42,10 +42,11 @@ package: debian $(V1) mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR) $(V1) rm -r debian +DEBIAN_DIR_FILES := changelog compat control copyright rules source/format .PHONY: debian debian: $(DEB_DIR) - $(V1) rm -rf debian - $(V1) cp -r $(DEB_DIR) debian + $(V1) rm -rf debian && mkdir debian + $(V1) cd $(DEB_DIR) $(foreach file,$(DEBIAN_DIR_FILES), && cp --parents $(file) $(ROOT_DIR)/debian) $(V1) cp -T package/linux/45-uav.rules debian/$(DEB_NAME).udev $(V1) $(SED_SCRIPT) debian/changelog debian/control ifeq ($(DEB_DIST), trusty) From f4955741bfe6d1b7faab95d5aee25abca95e629d Mon Sep 17 00:00:00 2001 From: James Duley Date: Sat, 7 May 2016 08:59:54 +0100 Subject: [PATCH 57/58] Add Qt < 5.6 compatibility again --- .../src/libs/osgearth/osgQtQuick/OSGViewport.cpp | 16 ++++++++++++++++ .../src/libs/osgearth/osgQtQuick/OSGViewport.hpp | 3 +++ 2 files changed, 19 insertions(+) diff --git a/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.cpp b/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.cpp index de46be9ea..36b6e9c38 100644 --- a/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.cpp +++ b/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.cpp @@ -607,11 +607,27 @@ QtKeyboardMap OSGViewport::Hidden::keyMap = QtKeyboardMap(); OSGViewport::OSGViewport(QQuickItem *parent) : Inherited(parent), h(new Hidden(this)) { // setClearBeforeRendering(false); +#if QT_VERSION >= QT_VERSION_CHECK(5, 6, 0) setMirrorVertically(true); +#endif setAcceptHoverEvents(true); setAcceptedMouseButtons(Qt::AllButtons); } +#if QT_VERSION < QT_VERSION_CHECK(5, 6, 0) +QSGNode *OSGViewport::updatePaintNode(QSGNode *node, QQuickItem::UpdatePaintNodeData *nodeData) +{ + if (!node) { + node = QQuickFramebufferObject::updatePaintNode(node, nodeData); + QSGSimpleTextureNode *n = static_cast(node); + if (n) + n->setTextureCoordinatesTransform(QSGSimpleTextureNode::MirrorVertically); + return node; + } + return QQuickFramebufferObject::updatePaintNode(node, nodeData); +} +#endif + OSGViewport::~OSGViewport() { delete h; diff --git a/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.hpp b/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.hpp index 46e6d366e..35a7e142c 100644 --- a/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.hpp +++ b/ground/gcs/src/libs/osgearth/osgQtQuick/OSGViewport.hpp @@ -93,6 +93,9 @@ signals: void busyChanged(bool busy); protected: +#if QT_VERSION < QT_VERSION_CHECK(5, 6, 0) + QSGNode *updatePaintNode(QSGNode *node, QQuickItem::UpdatePaintNodeData *nodeData) override; +#endif // QQuickItem void mousePressEvent(QMouseEvent *event); void mouseMoveEvent(QMouseEvent *event); From f6d5cbf4f800fd71ce8e1878ad06a1c036c5afc9 Mon Sep 17 00:00:00 2001 From: James Duley Date: Thu, 5 May 2016 23:17:13 +0100 Subject: [PATCH 58/58] Turn on osgearth for default debian package --- package/linux/deb.mk | 2 +- package/linux/debian/control | 2 +- package/linux/debian/rules | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/package/linux/deb.mk b/package/linux/deb.mk index d30691af6..79668b0ca 100644 --- a/package/linux/deb.mk +++ b/package/linux/deb.mk @@ -28,7 +28,7 @@ OPT_QT := qt56 TRUSTY_DEPS_SED := s/qml-module-.*/$(OPT_QT)quickcontrols/g; \ s/qt5-default.*/$(OPT_QT)-meta-minimal, $(OPT_QT)svg, $(OPT_QT)script, $(OPT_QT)serialport, $(OPT_QT)multimedia, $(OPT_QT)translations, $(OPT_QT)tools/g; -# Leave off Qt and ARM compiler dependencies if calling package target under the assumption that +# Leave off Qt and OSG dependencies if calling package target under the assumption that # OP is providing them or the user already has them installed because OP is already built. PACKAGE_DEPS_SED := s/python.*/python/;s/{misc:Depends}.*/{misc:Depends}/; diff --git a/package/linux/debian/control b/package/linux/debian/control index 3b0d49bc6..943829425 100644 --- a/package/linux/debian/control +++ b/package/linux/debian/control @@ -10,5 +10,5 @@ Vcs-Browser: Package: Architecture: any -Depends: ${shlibs:Depends}, ${misc:Depends}, qml-module-qtquick-controls, qml-module-qtquick-dialogs, qml-module-qtquick-xmllistmodel, qml-module-qtquick-localstorage, qml-module-qtquick-particles2, qml-module-qtquick-window2, qml-module-qtquick2 +Depends: ${shlibs:Depends}, ${misc:Depends}, openscenegraph-plugin-osgearth, qml-module-qtquick-controls, qml-module-qtquick-dialogs, qml-module-qtquick-xmllistmodel, qml-module-qtquick-localstorage, qml-module-qtquick-particles2, qml-module-qtquick-window2, qml-module-qtquick2 Description: diff --git a/package/linux/debian/rules b/package/linux/debian/rules index 66bbb414c..2fb9d4eb1 100755 --- a/package/linux/debian/rules +++ b/package/linux/debian/rules @@ -12,7 +12,7 @@ export DH_OPTIONS dh $@ override_dh_auto_configure: - $(MAKE) config_new GCS_EXTRA_CONF=osg WITH_PREBUILT_FW=$(CURDIR)/firmware + $(MAKE) config_new GCS_EXTRA_CONF='osg osgearth' WITH_PREBUILT_FW=$(CURDIR)/firmware override_dh_auto_build: dh_auto_build -- opfw_resource gcs