1 | // %flair:license{
|
---|
2 | // This file is part of the Flair framework distributed under the
|
---|
3 | // CECILL-C License, Version 1.0.
|
---|
4 | // %flair:license}
|
---|
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 {
|
---|
28 | namespace core {
|
---|
29 | class FrameworkManager;
|
---|
30 | class AhrsData;
|
---|
31 | class io_data;
|
---|
32 | }
|
---|
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 | }
|
---|
54 |
|
---|
55 | namespace flair {
|
---|
56 | namespace meta {
|
---|
57 |
|
---|
58 | /*! \class UavStateMachine
|
---|
59 | *
|
---|
60 | * \brief State machine for UAV
|
---|
61 | * The Thread is created with
|
---|
62 | * the FrameworkManager as parent. FrameworkManager must be created before.
|
---|
63 | * The Thread is synchronized with Ahrs, unless a period is set with SetPeriodUS or
|
---|
64 | * SetPeriodMS
|
---|
65 | */
|
---|
66 |
|
---|
67 | class UavStateMachine : public core::Thread {
|
---|
68 | protected:
|
---|
69 | enum class AltitudeMode_t { Manual, Custom };
|
---|
70 | const AltitudeMode_t &GetAltitudeMode(void) const { return altitudeMode; }
|
---|
71 | bool SetAltitudeMode(const AltitudeMode_t &altitudeMode);
|
---|
72 |
|
---|
73 | // uses TrajectoryGenerator1D *altitudeTrajectory to go to desiredAltitude
|
---|
74 | // available in mode AltitudeMode_t::Manual
|
---|
75 | // return true if goto is possible
|
---|
76 | bool GotoAltitude(float desiredAltitude);
|
---|
77 |
|
---|
78 | enum class OrientationMode_t { Manual, Custom };
|
---|
79 | const OrientationMode_t &GetOrientationMode(void) const {
|
---|
80 | return orientationMode;
|
---|
81 | }
|
---|
82 | bool SetOrientationMode(const OrientationMode_t &orientationMode);
|
---|
83 |
|
---|
84 | enum class ThrustMode_t { Default, Custom };
|
---|
85 | const ThrustMode_t &GetThrustMode() const { return thrustMode; }
|
---|
86 | bool SetThrustMode(const ThrustMode_t &thrustMode);
|
---|
87 |
|
---|
88 | enum class TorqueMode_t { Default, Custom };
|
---|
89 | const TorqueMode_t &GetTorqueMode(void) const { return torqueMode; }
|
---|
90 | bool SetTorqueMode(const TorqueMode_t &torqueMode);
|
---|
91 |
|
---|
92 | enum class Event_t {
|
---|
93 | EnteringFailSafeMode,
|
---|
94 | EnteringControlLoop,
|
---|
95 | StartLanding,
|
---|
96 | FinishLanding,
|
---|
97 | Stopped,
|
---|
98 | TakingOff,
|
---|
99 | EmergencyStop,
|
---|
100 | Stabilized, // as soon as uav is 3cm far from the ground
|
---|
101 | ZTrajectoryFinished,
|
---|
102 | };
|
---|
103 |
|
---|
104 | UavStateMachine(sensor::TargetController* controller);
|
---|
105 | ~UavStateMachine();
|
---|
106 |
|
---|
107 | const core::Quaternion &GetCurrentQuaternion(void) const;
|
---|
108 |
|
---|
109 | const core::Vector3D &GetCurrentAngularSpeed(void) const;
|
---|
110 |
|
---|
111 | void Land(void);
|
---|
112 | void EmergencyLand(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);
|
---|
120 |
|
---|
121 | virtual const core::AhrsData *GetOrientation(void) const;
|
---|
122 | const core::AhrsData *GetDefaultOrientation(void) const;
|
---|
123 |
|
---|
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!
|
---|
128 |
|
---|
129 | gui::GridLayout *GetButtonsLayout(void) const;
|
---|
130 | virtual void ExtraSecurityCheck(void){};
|
---|
131 | virtual void ExtraCheckJoystick(void){};
|
---|
132 | virtual void ExtraCheckPushButton(void){};
|
---|
133 |
|
---|
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);
|
---|
141 |
|
---|
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);
|
---|
153 |
|
---|
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);
|
---|
165 |
|
---|
166 | /*!
|
---|
167 | * \brief Get Torques
|
---|
168 | *
|
---|
169 | * \return torques current torques
|
---|
170 | */
|
---|
171 | // const core::Euler &GetTorques() const;
|
---|
172 |
|
---|
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);
|
---|
184 |
|
---|
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);
|
---|
196 |
|
---|
197 | /*!
|
---|
198 | * \brief Get Thrust
|
---|
199 | *
|
---|
200 | * \return current thrust
|
---|
201 | */
|
---|
202 | // float GetThrust() const;
|
---|
203 |
|
---|
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);
|
---|
215 |
|
---|
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);
|
---|
227 |
|
---|
228 | const sensor::TargetController *GetJoystick(void) const;
|
---|
229 | MetaDualShock3 *joy;
|
---|
230 |
|
---|
231 | gui::Tab *setupLawTab, *graphLawTab;
|
---|
232 |
|
---|
233 | private:
|
---|
234 | /*!
|
---|
235 | \enum AltitudeState_t
|
---|
236 | \brief States of the altitude state machine
|
---|
237 | */
|
---|
238 | enum class AltitudeState_t {
|
---|
239 | Stopped, /*!< the uav motors are stopped */
|
---|
240 | TakingOff, /*!< take off initiated. Motors accelerate progressively until
|
---|
241 | the UAV lift up */
|
---|
242 | Stabilized, /*!< the uav is actively maintaining its altitude */
|
---|
243 | StartLanding, /*!< landing initiated. Altitude is required to reach the
|
---|
244 | landing altitude (0 by default) */
|
---|
245 | FinishLanding /*!< motors are gradually stopped */
|
---|
246 | };
|
---|
247 | AltitudeState_t altitudeState;
|
---|
248 | void ProcessAltitudeFiniteStateMachine();
|
---|
249 | void ComputeReferenceAltitude(float &refAltitude, float &refVerticalVelocity);
|
---|
250 |
|
---|
251 | float groundAltitude; // effective altitude when the uav leaves the ground
|
---|
252 | float currentAltitude, currentVerticalSpeed;
|
---|
253 |
|
---|
254 | bool failSafeMode;
|
---|
255 | void SecurityCheck(void);
|
---|
256 | void MandatorySecurityCheck(void);
|
---|
257 | void CheckJoystick();
|
---|
258 | void GenericCheckJoystick();
|
---|
259 | void CheckPushButton(void);
|
---|
260 | void GenericCheckPushButton(void);
|
---|
261 | void Run(void);
|
---|
262 | void StopMotors(void);
|
---|
263 | bool IsValuePossible(float value,std::string desc);
|
---|
264 |
|
---|
265 | meta::Uav *uav;
|
---|
266 | sensor::TargetController *controller;
|
---|
267 |
|
---|
268 | core::Quaternion currentQuaternion;
|
---|
269 | core::Vector3D currentAngularSpeed;
|
---|
270 |
|
---|
271 | const core::AhrsData *ComputeReferenceOrientation(void);
|
---|
272 |
|
---|
273 | void ComputeOrientation(void);
|
---|
274 | void ComputeAltitude(void);
|
---|
275 |
|
---|
276 | void ComputeTorques(void);
|
---|
277 | core::Euler currentTorques, savedDefaultTorques;
|
---|
278 | bool needToComputeDefaultTorques;
|
---|
279 |
|
---|
280 | void ComputeThrust(void);
|
---|
281 | float currentThrust, savedDefaultThrust;
|
---|
282 | bool needToComputeDefaultThrust;
|
---|
283 |
|
---|
284 | gui::PushButton *button_kill, *button_take_off, *button_land,
|
---|
285 | *button_start_log, *button_stop_log;
|
---|
286 | gui::GridLayout *buttonslayout;
|
---|
287 | gui::DoubleSpinBox *desiredTakeoffAltitude, *desiredLandingAltitude;
|
---|
288 | AltitudeMode_t altitudeMode;
|
---|
289 | OrientationMode_t orientationMode;
|
---|
290 | ThrustMode_t thrustMode;
|
---|
291 | TorqueMode_t torqueMode;
|
---|
292 | bool flagBatteryLow;
|
---|
293 | bool flagConnectionLost;
|
---|
294 | bool flagCriticalSensorLost;
|
---|
295 | bool flagZTrajectoryFinished;
|
---|
296 | bool safeToFly;
|
---|
297 | filter::NestedSat *uRoll, *uPitch;
|
---|
298 | filter::Pid *uYaw;
|
---|
299 | filter::PidThrust *uZ;
|
---|
300 | filter::TrajectoryGenerator1D *altitudeTrajectory;
|
---|
301 | };
|
---|
302 | };
|
---|
303 | };
|
---|
304 | #endif // UAVSTATEMACHINE_H
|
---|