[9] | 1 | // %flair:license{
|
---|
[13] | 2 | // This file is part of the Flair framework distributed under the
|
---|
| 3 | // CECILL-C License, Version 1.0.
|
---|
[9] | 4 | // %flair:license}
|
---|
[7] | 5 | // created: 2014/04/29
|
---|
| 6 | // filename: UavStateMachine.h
|
---|
| 7 | //
|
---|
| 8 | // author: Gildas Bayard, Guillaume Sanahuja
|
---|
| 9 | // Copyright Heudiasyc UMR UTC/CNRS 7253
|
---|
| 10 | //
|
---|
| 11 | // version: $Id: $
|
---|
| 12 | //
|
---|
| 13 | // purpose: state machine for UAV
|
---|
| 14 | //
|
---|
| 15 | //
|
---|
| 16 | /*********************************************************************/
|
---|
| 17 |
|
---|
| 18 | #ifndef UAVSTATEMACHINE_H
|
---|
| 19 | #define UAVSTATEMACHINE_H
|
---|
| 20 |
|
---|
| 21 | #include <Thread.h>
|
---|
| 22 | #include <Vector2D.h>
|
---|
| 23 | #include <Vector3D.h>
|
---|
| 24 | #include <Euler.h>
|
---|
| 25 | #include <Quaternion.h>
|
---|
| 26 |
|
---|
| 27 | namespace flair {
|
---|
[13] | 28 | namespace core {
|
---|
| 29 | class FrameworkManager;
|
---|
| 30 | class AhrsData;
|
---|
| 31 | class io_data;
|
---|
[7] | 32 | }
|
---|
[13] | 33 | namespace gui {
|
---|
| 34 | class PushButton;
|
---|
| 35 | class GridLayout;
|
---|
| 36 | class Tab;
|
---|
| 37 | class DoubleSpinBox;
|
---|
| 38 | }
|
---|
| 39 | namespace filter {
|
---|
| 40 | class ControlLaw;
|
---|
| 41 | class NestedSat;
|
---|
| 42 | class Pid;
|
---|
| 43 | class PidThrust;
|
---|
| 44 | class TrajectoryGenerator1D;
|
---|
| 45 | }
|
---|
| 46 | namespace sensor {
|
---|
| 47 | class TargetController;
|
---|
| 48 | }
|
---|
| 49 | namespace meta {
|
---|
| 50 | class MetaDualShock3;
|
---|
| 51 | class Uav;
|
---|
| 52 | }
|
---|
| 53 | }
|
---|
[7] | 54 |
|
---|
[13] | 55 | namespace flair {
|
---|
| 56 | namespace meta {
|
---|
[7] | 57 |
|
---|
[13] | 58 | /*! \class UavStateMachine
|
---|
[7] | 59 | *
|
---|
| 60 | * \brief State machine for UAV
|
---|
| 61 | *
|
---|
[13] | 62 | * thread synchronized with ahrs, unless a period is set with SetPeriodUS or
|
---|
| 63 | *SetPeriodMS
|
---|
[7] | 64 | */
|
---|
| 65 |
|
---|
[13] | 66 | class UavStateMachine : public core::Thread {
|
---|
| 67 | protected:
|
---|
| 68 | enum class AltitudeMode_t { Manual, Custom };
|
---|
| 69 | const AltitudeMode_t &GetAltitudeMode(void) const { return altitudeMode; }
|
---|
| 70 | bool SetAltitudeMode(const AltitudeMode_t &altitudeMode);
|
---|
[7] | 71 |
|
---|
[13] | 72 | // uses TrajectoryGenerator1D *altitudeTrajectory to go to desiredAltitude
|
---|
| 73 | // available in mode AltitudeMode_t::Manual
|
---|
| 74 | // return true if goto is possible
|
---|
| 75 | bool GotoAltitude(float desiredAltitude);
|
---|
[7] | 76 |
|
---|
[13] | 77 | enum class OrientationMode_t { Manual, Custom };
|
---|
| 78 | const OrientationMode_t &GetOrientationMode(void) const {
|
---|
| 79 | return orientationMode;
|
---|
| 80 | }
|
---|
| 81 | bool SetOrientationMode(const OrientationMode_t &orientationMode);
|
---|
[7] | 82 |
|
---|
[13] | 83 | enum class ThrustMode_t { Default, Custom };
|
---|
| 84 | const ThrustMode_t &GetThrustMode() const { return thrustMode; }
|
---|
| 85 | bool SetThrustMode(const ThrustMode_t &thrustMode);
|
---|
[7] | 86 |
|
---|
[13] | 87 | enum class TorqueMode_t { Default, Custom };
|
---|
| 88 | const TorqueMode_t &GetTorqueMode(void) const { return torqueMode; }
|
---|
| 89 | bool SetTorqueMode(const TorqueMode_t &torqueMode);
|
---|
[7] | 90 |
|
---|
[13] | 91 | enum class Event_t {
|
---|
| 92 | EnteringFailSafeMode,
|
---|
| 93 | EnteringControlLoop,
|
---|
| 94 | StartLanding,
|
---|
| 95 | FinishLanding,
|
---|
| 96 | Stopped,
|
---|
| 97 | TakingOff,
|
---|
| 98 | EmergencyStop,
|
---|
| 99 | Stabilized, // as soon as uav is 3cm far from the ground
|
---|
| 100 | ZTrajectoryFinished,
|
---|
| 101 | };
|
---|
[7] | 102 |
|
---|
[13] | 103 | UavStateMachine(meta::Uav *uav, uint16_t ds3Port = 20000);
|
---|
| 104 | ~UavStateMachine();
|
---|
[7] | 105 |
|
---|
[13] | 106 | const core::Quaternion &GetCurrentQuaternion(void) const;
|
---|
[7] | 107 |
|
---|
[13] | 108 | const core::Vector3D &GetCurrentAngularSpeed(void) const;
|
---|
[7] | 109 |
|
---|
[13] | 110 | const meta::Uav *GetUav(void) const;
|
---|
[7] | 111 |
|
---|
[13] | 112 | void Land(void);
|
---|
| 113 | void TakeOff(void);
|
---|
| 114 | void EmergencyStop(void);
|
---|
| 115 | //! Used to signal an event
|
---|
| 116 | /*!
|
---|
| 117 | \param event the event which occured
|
---|
| 118 | */
|
---|
| 119 | virtual void SignalEvent(Event_t event);
|
---|
[7] | 120 |
|
---|
[13] | 121 | virtual const core::AhrsData *GetOrientation(void) const;
|
---|
| 122 | const core::AhrsData *GetDefaultOrientation(void) const;
|
---|
[7] | 123 |
|
---|
[13] | 124 | virtual void AltitudeValues(float &z, float &dz) const; // in uav coordinate!
|
---|
| 125 | void EnterFailSafeMode(void);
|
---|
| 126 | bool ExitFailSafeMode(void);
|
---|
| 127 | void FailSafeAltitudeValues(float &z, float &dz) const; // in uav coordinate!
|
---|
[7] | 128 |
|
---|
[13] | 129 | gui::GridLayout *GetButtonsLayout(void) const;
|
---|
| 130 | virtual void ExtraSecurityCheck(void){};
|
---|
| 131 | virtual void ExtraCheckJoystick(void){};
|
---|
| 132 | virtual void ExtraCheckPushButton(void){};
|
---|
[7] | 133 |
|
---|
[13] | 134 | void GetDefaultReferenceAltitude(float &refAltitude,
|
---|
| 135 | float &refVerticalVelocity);
|
---|
| 136 | virtual void GetReferenceAltitude(float &refAltitude,
|
---|
| 137 | float &refVerticalVelocity);
|
---|
| 138 | // float GetDefaultThrustOffset(void);
|
---|
| 139 | const core::AhrsData *GetDefaultReferenceOrientation(void) const;
|
---|
| 140 | virtual const core::AhrsData *GetReferenceOrientation(void);
|
---|
[7] | 141 |
|
---|
[13] | 142 | /*!
|
---|
| 143 | * \brief Compute Custom Torques
|
---|
| 144 | *
|
---|
| 145 | * Reimplement this method to use TorqueMode_t::Custom. \n
|
---|
| 146 | * This method is called internally by UavStateMachine, do not call it by
|
---|
| 147 | *yourself. \n
|
---|
| 148 | * See GetTorques if you need torques values.
|
---|
| 149 | *
|
---|
| 150 | * \param torques custom torques
|
---|
| 151 | */
|
---|
| 152 | virtual void ComputeCustomTorques(core::Euler &torques);
|
---|
[7] | 153 |
|
---|
[13] | 154 | /*!
|
---|
| 155 | * \brief Compute Default Torques
|
---|
| 156 | *
|
---|
| 157 | * This method is called internally by UavStateMachine when using
|
---|
| 158 | *TorqueMode_t::Default. \n
|
---|
| 159 | * Torques are only computed once by loop, other calls to this method will use
|
---|
| 160 | *previously computed torques.
|
---|
| 161 | *
|
---|
| 162 | * \param torques default torques
|
---|
| 163 | */
|
---|
| 164 | void ComputeDefaultTorques(core::Euler &torques);
|
---|
[7] | 165 |
|
---|
[13] | 166 | /*!
|
---|
| 167 | * \brief Get Torques
|
---|
| 168 | *
|
---|
| 169 | * \return torques current torques
|
---|
| 170 | */
|
---|
| 171 | // const core::Euler &GetTorques() const;
|
---|
[7] | 172 |
|
---|
[13] | 173 | /*!
|
---|
| 174 | * \brief Compute Custom Thrust
|
---|
| 175 | *
|
---|
| 176 | * Reimplement this method to use ThrustMode_t::Custom. \n
|
---|
| 177 | * This method is called internally by UavStateMachine, do not call it by
|
---|
| 178 | *yourself. \n
|
---|
| 179 | * See GetThrust if you need thrust value.
|
---|
| 180 | *
|
---|
| 181 | * \return custom Thrust
|
---|
| 182 | */
|
---|
| 183 | virtual float ComputeCustomThrust(void);
|
---|
[7] | 184 |
|
---|
[13] | 185 | /*!
|
---|
| 186 | * \brief Compute Default Thrust
|
---|
| 187 | *
|
---|
| 188 | * This method is called internally by UavStateMachine when using
|
---|
| 189 | *ThrustMode_t::Default. \n
|
---|
| 190 | * Thrust is only computed once by loop, other calls to this method will use
|
---|
| 191 | *previously computed thrust.
|
---|
| 192 | *
|
---|
| 193 | * \return default thrust
|
---|
| 194 | */
|
---|
| 195 | float ComputeDefaultThrust(void);
|
---|
[7] | 196 |
|
---|
[13] | 197 | /*!
|
---|
| 198 | * \brief Get Thrust
|
---|
| 199 | *
|
---|
| 200 | * \return current thrust
|
---|
| 201 | */
|
---|
| 202 | // float GetThrust() const;
|
---|
[7] | 203 |
|
---|
[13] | 204 | /*!
|
---|
| 205 | * \brief Add an IODevice to the control law logs
|
---|
| 206 | *
|
---|
| 207 | * The IODevice will be automatically logged among the Uz logs,
|
---|
| 208 | * if logging is enabled (see IODevice::SetDataToLog,
|
---|
| 209 | *FrameworkManager::StartLog
|
---|
| 210 | * and FrameworkManager::AddDeviceToLog). \n
|
---|
| 211 | *
|
---|
| 212 | * \param device IODevice to log
|
---|
| 213 | */
|
---|
| 214 | void AddDeviceToControlLawLog(const core::IODevice *device);
|
---|
[7] | 215 |
|
---|
[13] | 216 | /*!
|
---|
| 217 | * \brief Add an io_data to the control law logs
|
---|
| 218 | *
|
---|
| 219 | * The io_data will be automatically logged among the Uz logs,
|
---|
| 220 | * if logging is enabled (see IODevice::SetDataToLog,
|
---|
| 221 | *FrameworkManager::StartLog
|
---|
| 222 | * and FrameworkManager::AddDeviceToLog). \n
|
---|
| 223 | *
|
---|
| 224 | * \param data io_data to log
|
---|
| 225 | */
|
---|
| 226 | void AddDataToControlLawLog(const core::io_data *data);
|
---|
[7] | 227 |
|
---|
[13] | 228 | const sensor::TargetController *GetJoystick(void) const;
|
---|
[7] | 229 |
|
---|
[13] | 230 | gui::Tab *setupLawTab, *graphLawTab;
|
---|
[7] | 231 |
|
---|
[13] | 232 | private:
|
---|
| 233 | /*!
|
---|
| 234 | \enum AltitudeState_t
|
---|
| 235 | \brief States of the altitude state machine
|
---|
| 236 | */
|
---|
| 237 | enum class AltitudeState_t {
|
---|
| 238 | Stopped, /*!< the uav motors are stopped */
|
---|
| 239 | TakingOff, /*!< take off initiated. Motors accelerate progressively until
|
---|
| 240 | the UAV lift up */
|
---|
| 241 | Stabilized, /*!< the uav is actively maintaining its altitude */
|
---|
| 242 | StartLanding, /*!< landing initiated. Altitude is required to reach the
|
---|
| 243 | landing altitude (0 by default) */
|
---|
| 244 | FinishLanding /*!< motors are gradually stopped */
|
---|
| 245 | };
|
---|
| 246 | AltitudeState_t altitudeState;
|
---|
| 247 | void ProcessAltitudeFiniteStateMachine();
|
---|
| 248 | void ComputeReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
|
---|
[7] | 249 |
|
---|
[13] | 250 | float groundAltitude; // effective altitude when the uav leaves the ground
|
---|
| 251 | float currentAltitude, currentVerticalSpeed;
|
---|
[7] | 252 |
|
---|
[13] | 253 | bool failSafeMode;
|
---|
| 254 | void SecurityCheck(void);
|
---|
| 255 | void MandatorySecurityCheck(void);
|
---|
| 256 | void CheckJoystick();
|
---|
| 257 | void GenericCheckJoystick();
|
---|
| 258 | void CheckPushButton(void);
|
---|
| 259 | void GenericCheckPushButton(void);
|
---|
| 260 | void Run(void);
|
---|
| 261 | void StopMotors(void);
|
---|
[7] | 262 |
|
---|
[13] | 263 | meta::Uav *uav;
|
---|
[7] | 264 |
|
---|
[13] | 265 | core::Quaternion currentQuaternion;
|
---|
| 266 | core::Vector3D currentAngularSpeed;
|
---|
[7] | 267 |
|
---|
[13] | 268 | const core::AhrsData *ComputeReferenceOrientation(void);
|
---|
[7] | 269 |
|
---|
[13] | 270 | void ComputeOrientation(void);
|
---|
| 271 | void ComputeAltitude(void);
|
---|
[7] | 272 |
|
---|
[13] | 273 | void ComputeTorques(void);
|
---|
| 274 | core::Euler currentTorques, savedDefaultTorques;
|
---|
| 275 | bool needToComputeDefaultTorques;
|
---|
[7] | 276 |
|
---|
[13] | 277 | void ComputeThrust(void);
|
---|
| 278 | float currentThrust, savedDefaultThrust;
|
---|
| 279 | bool needToComputeDefaultThrust;
|
---|
[7] | 280 |
|
---|
[13] | 281 | gui::PushButton *button_kill, *button_take_off, *button_land,
|
---|
| 282 | *button_start_log, *button_stop_log;
|
---|
| 283 | gui::GridLayout *buttonslayout;
|
---|
| 284 | gui::DoubleSpinBox *desiredTakeoffAltitude, *desiredLandingAltitude;
|
---|
| 285 | AltitudeMode_t altitudeMode;
|
---|
| 286 | OrientationMode_t orientationMode;
|
---|
| 287 | ThrustMode_t thrustMode;
|
---|
| 288 | TorqueMode_t torqueMode;
|
---|
| 289 | bool flagBatteryLow;
|
---|
| 290 | bool flagConnectionLost;
|
---|
| 291 | bool flagZTrajectoryFinished;
|
---|
| 292 | filter::NestedSat *uRoll, *uPitch;
|
---|
| 293 | filter::Pid *uYaw;
|
---|
| 294 | filter::PidThrust *uZ;
|
---|
[7] | 295 |
|
---|
[13] | 296 | MetaDualShock3 *joy;
|
---|
| 297 | filter::TrajectoryGenerator1D *altitudeTrajectory;
|
---|
[7] | 298 | };
|
---|
| 299 | };
|
---|
| 300 | };
|
---|
| 301 | #endif // UAVSTATEMACHINE_H
|
---|