MAV'RIC
mav_modes.h
1 /*******************************************************************************
2  * Copyright (c) 2009-2014, MAV'RIC Development Team
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * 3. Neither the name of the copyright holder nor the names of its contributors
16  * may be used to endorse or promote products derived from this software without
17  * specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  ******************************************************************************/
31 
32 /*******************************************************************************
33  * \file mav_mode.h
34  *
35  * \author MAV'RIC Team
36  * \author Julien Lecoeur
37  *
38  * \brief Place where the mav modes and flags are defined
39  *
40  ******************************************************************************/
41 
42 
43 #ifndef MAV_MODE_H
44 #define MAV_MODE_H
45 
46 #include "mavlink_stream.h"
47 #include <stdint.h>
48 #include <stdbool.h>
49 
50 
51 /*
52  * \brief enum for defining ARM/DISARM status
53  */
54 typedef enum
55 {
56  ARMED_OFF = 0,
57  ARMED_ON = 1,
58 } mode_flag_armed_t;
59 
60 
61 /*
62  * \brief enum for defining manual piloting mode
63  */
64 typedef enum
65 {
66  MANUAL_OFF = 0,
67  MANUAL_ON = 1,
68 } mode_flag_manual_t;
69 
70 
71 /*
72  * \brief enum for defining simulation mode
73  */
74 typedef enum
75 {
76  HIL_OFF = 0,
77  HIL_ON = 1,
78 } mode_flag_hil_t;
79 
80 
81 /*
82  * \brief enum for defining stabilization piloting mode
83  */
84 typedef enum
85 {
86  STABILISE_OFF = 0,
87  STABILISE_ON = 1,
88 } mode_flag_stabilise_t;
89 
90 
91 /*
92  * \brief enum for defining hover piloting mode
93  */
94 typedef enum
95 {
96  GUIDED_OFF = 0,
97  GUIDED_ON = 1,
98 } mode_flag_guided_t;
99 
100 
101 /*
102  * \brief enum for defining waypoint navigation piloting mode
103  */
104 typedef enum
105 {
106  AUTO_OFF = 0,
107  AUTO_ON = 1,
108 } mode_flag_auto_t;
109 
110 
111 /*
112  * \brief enum for defining testing mode
113  */
114 typedef enum
115 {
116  TEST_OFF = 0,
117  TEST_ON = 1,
118 } mode_flag_test_t;
119 
120 
121 /*
122  * \brief enum for defining custom mode
123  */
124 typedef enum
125 {
126  CUSTOM_OFF = 0,
127  CUSTOM_ON = 1,
128 } mode_flag_custom_t;
129 
130 
131 /*
132  * \brief Define the structure for the flag corresponding to each mode
133  */
134 typedef struct
135 {
136  mode_flag_armed_t ARMED : 1;
137  mode_flag_manual_t MANUAL : 1;
138  mode_flag_hil_t HIL : 1;
139  mode_flag_stabilise_t STABILISE : 1;
140  mode_flag_guided_t GUIDED : 1;
141  mode_flag_auto_t AUTO : 1;
142  mode_flag_test_t TEST : 1;
143  mode_flag_custom_t CUSTOM : 1;
145 
146 
147 typedef union
148 {
149  uint8_t byte;
150  // unamed bitfield structure, use to access directly the flags
151  struct
152  {
153  mode_flag_armed_t ARMED : 1;
154  mode_flag_manual_t MANUAL : 1;
155  mode_flag_hil_t HIL : 1;
156  mode_flag_stabilise_t STABILISE : 1;
157  mode_flag_guided_t GUIDED : 1;
158  mode_flag_auto_t AUTO : 1;
159  mode_flag_test_t TEST : 1;
160  mode_flag_custom_t CUSTOM : 1;
161  };
162  // identical bitfield, but named (useful for initialisation)
163  struct
164  {
165  mode_flag_armed_t ARMED : 1;
166  mode_flag_manual_t MANUAL : 1;
167  mode_flag_hil_t HIL : 1;
168  mode_flag_stabilise_t STABILISE : 1;
169  mode_flag_guided_t GUIDED : 1;
170  mode_flag_auto_t AUTO : 1;
171  mode_flag_test_t TEST : 1;
172  mode_flag_custom_t CUSTOM : 1;
173  } flags;
174 } mav_mode_t;
175 
176 
177 /*
178  * \brief enum for defining mode flags
179  */
180 typedef enum
181 {
182  MODE_FLAG_CUSTOM = 0,
183  MODE_FLAG_TEST = 1,
184  MODE_FLAG_AUTO = 2,
185  MODE_FLAG_GUIDED = 3,
186  MODE_FLAG_STABILISE = 4,
187  MODE_FLAG_HIL = 5,
188  MODE_FLAG_MANUAL = 6,
189  MODE_FLAG_ARMED = 7,
190 } mode_flags_t;
191 
192 
193 typedef enum MAV_MODE_FLAG mav_flag_mask_t;
194 
195 typedef enum MAV_STATE mav_state_t;
196 
197 
198 /*
199  * \brief enum for defining modes
200  */
201 typedef enum
202 {
203  MAV_MODE_PRE = 0,
204  MAV_MODE_SAFE = 64,
205  MAV_MODE_ATTITUDE_CONTROL = 192,
206  MAV_MODE_VELOCITY_CONTROL = 208,
207  MAV_MODE_POSITION_HOLD = 216,
208  MAV_MODE_GPS_NAVIGATION = 156
209 } mav_mode_predefined_t;
210 
211 
212 /*
213  * \brief enum for defining custom mode
214  */
215 typedef enum
216 {
217  CUSTOM_BASE_MODE = 0,
218  CUST_CLIMB_TO_SAFE_ALT = 1,
219  CUST_FLY_TO_HOME_WP = 2,
220  CUST_CRITICAL_LAND = 4,
221 
222  CUST_DESCENT_TO_SMALL_ALTITUDE = 8,
223  CUST_DESCENT_TO_GND = 16,
224 
225  CUST_COLLISION_AVOIDANCE = 32
226 }mav_mode_custom_t;
227 
228 /*
229  * \brief Returns whether motors are armed or not
230  *
231  * \param mav_mode correspond to the mode in which the MAV is
232  *
233  * \return true if motor are armed, false otherwise
234  */
235 static inline bool mav_modes_is_armed(const mav_mode_t mav_mode)
236 {
237  if ( mav_mode.ARMED == ARMED_ON )
238  {
239  return true;
240  }
241  else
242  {
243  return false;
244  }
245 }
246 
247 /*
248  * \brief Returns whether the MAV is in simulation mode
249  *
250  * \param mav_mode correspond to the mode in which the MAV is
251  *
252  * \return true if MAV is in simulation mode, false otherwise
253  */
254 static inline bool mav_modes_is_hil(const mav_mode_t mav_mode)
255 {
256  if ( mav_mode.HIL == HIL_ON )
257  {
258  return true;
259  }
260  else
261  {
262  return false;
263  }
264 }
265 
266 
267 /*
268  * \brief Returns whether MAV is in manual piloting mode
269  *
270  * \param mav_mode correspond to the mode in which the MAV is
271  *
272  * \return true if MAv is in manual piloting mode, false otherwise
273  */
274 static inline bool mav_modes_is_manual(const mav_mode_t mav_mode)
275 {
276  if ( mav_mode.MANUAL == MANUAL_ON )
277  {
278  return true;
279  }
280  else
281  {
282  return false;
283  }
284 }
285 
286 
287 /*
288  * \brief Returns whether MAV is in stabilise piloting mode
289  *
290  * \param mav_mode correspond to the mode in which the MAV is
291  *
292  * \return true if MAv is in stabilise piloting mode, false otherwise
293  */
294 static inline bool mav_modes_is_stabilise(const mav_mode_t mav_mode)
295 {
296  if ( mav_mode.STABILISE == STABILISE_ON )
297  {
298  return true;
299  }
300  else
301  {
302  return false;
303  }
304 }
305 
306 
307 /*
308  * \brief Returns whether MAV is in hover piloting mode
309  *
310  * \param mav_mode correspond to the mode in which the MAV is
311  *
312  * \return true if MAv is in hover piloting mode, false otherwise
313  */
314 static inline bool mav_modes_is_guided(const mav_mode_t mav_mode)
315 {
316  if ( mav_mode.GUIDED == GUIDED_ON )
317  {
318  return true;
319  }
320  else
321  {
322  return false;
323  }
324 }
325 
326 /*
327  * \brief Returns whether MAV is in waypoint navigation piloting mode
328  *
329  * \param mav_mode correspond to the mode in which the MAV is
330  *
331  * \return true if MAv is in waypoint navigation piloting mode, false otherwise
332  */
333 static inline bool mav_modes_is_auto(const mav_mode_t mav_mode)
334 {
335  if ( mav_mode.AUTO == AUTO_ON )
336  {
337  return true;
338  }
339  else
340  {
341  return false;
342  }
343 }
344 
345 
346 /*
347  * \brief Returns whether MAV is in test mode
348  *
349  * \param mav_mode correspond to the mode in which the MAV is
350  *
351  * \return true if MAv is in test mode, false otherwise
352  */
353 static inline bool mav_modes_is_test(const mav_mode_t mav_mode)
354 {
355  if ( mav_mode.TEST == TEST_ON )
356  {
357  return true;
358  }
359  else
360  {
361  return false;
362  }
363 }
364 
365 
366 /*
367  * \brief Returns whether MAV is in custom mode
368  *
369  * \param mav_mode correspond to the mode in which the MAV is
370  *
371  * \return true if MAv is in custom mode, false otherwise
372  */
373 static inline bool mav_modes_is_custom(const mav_mode_t mav_mode)
374 {
375  if ( mav_mode.CUSTOM == CUSTOM_ON )
376  {
377  return true;
378  }
379  else
380  {
381  return false;
382  }
383 }
384 
385 /*
386  * \brief compare two MAV modes
387  *
388  * \param mode1 correspond to one mode in which the MAV may be
389  * \param mode2 correspond to an other mode in which the MAV may be
390  *
391  * \return true if modes are equal, false otherwise
392  */
393 static inline bool mav_modes_are_equal(const mav_mode_t mode1, const mav_mode_t mode2)
394 {
395  if ( mode1.byte == mode2.byte )
396  {
397  return true;
398  }
399  else
400  {
401  return false;
402  }
403 }
404 
405 /*
406  * \brief compare two MAV modes, whatever simulation flag is set or not
407  *
408  * \param mode1 correspond to one mode in which the MAV may be
409  * \param mode2 correspond to an other mode in which the MAV may be
410  *
411  * \return true if modes are equal, false otherwise
412  */
413 static inline bool mav_modes_are_equal_wo_hil(const mav_mode_t mode1, const mav_mode_t mode2)
414 {
415  mav_mode_t mode1_ = mode1;
416  mav_mode_t mode2_ = mode2;
417 
418  mode1_.HIL = HIL_OFF;
419  mode2_.HIL = HIL_OFF;
420 
421  return mav_modes_are_equal(mode1_, mode2_);
422 }
423 
424 
425 /*
426  * \brief compare two MAV modes, whatever armed flag is set or not
427  *
428  * \param mode1 correspond to one mode in which the MAV may be
429  * \param mode2 correspond to an other mode in which the MAV may be
430  *
431  * \return true if modes are equal, false otherwise
432  */
433 static inline bool mav_modes_are_equal_wo_armed(const mav_mode_t mode1, const mav_mode_t mode2)
434 {
435  mav_mode_t mode1_ = mode1;
436  mav_mode_t mode2_ = mode2;
437 
438  mode1_.ARMED = ARMED_OFF;
439  mode2_.ARMED = ARMED_OFF;
440 
441  return mav_modes_are_equal(mode1_, mode2_);
442 }
443 
444 
445 /*
446  * \brief compare two MAV modes, whatever simulation and armed flag is set or not
447  *
448  * \param mode1 correspond to one mode in which the MAV may be
449  * \param mode2 correspond to an other mode in which the MAV may be
450  *
451  * \return true if modes are equal, false otherwise
452  */
453 static inline bool mav_modes_are_equal_wo_hil_and_armed(const mav_mode_t mode1, const mav_mode_t mode2)
454 {
455  mav_mode_t mode1_ = mode1;
456  mav_mode_t mode2_ = mode2;
457 
458  mode1_.HIL = HIL_OFF;
459  mode2_.HIL = HIL_OFF;
460  mode1_.ARMED = ARMED_OFF;
461  mode2_.ARMED = ARMED_OFF;
462 
463  return mav_modes_are_equal(mode1_, mode2_);
464 }
465 
466 
467 /*
468  * \brief Returns the corresponding MAV mode
469  *
470  * \param armed correspond to the armed flag
471  * \param hil correspond to the simulation flag
472  * \param manual correspond to the maual flag
473  * \param stabilise correspond to the stabilization flag
474  * \param guided correspond to the hover flag
475  * \param auto correspond to the waypoint navigation flag
476  * \param test correspond to the test flag
477  * \param custom correspond to the custom flag
478  *
479  * \return the MAV mode corresponding to the flags
480  */
481 static inline mav_mode_t mav_modes_get_from_flags(const mode_flag_armed_t armed, const mode_flag_hil_t hil, const mode_flag_manual_t manual, const mode_flag_stabilise_t stabilise, const mode_flag_guided_t guided, const mode_flag_auto_t autoo, const mode_flag_test_t test, const mode_flag_custom_t custom)
482 {
483  mav_mode_t mode;
484 
485  mode.ARMED = armed;
486  mode.HIL = hil;
487  mode.MANUAL = manual;
488  mode.STABILISE = stabilise;
489  mode.GUIDED = guided;
490  mode.AUTO = autoo;
491  mode.TEST = test;
492  mode.CUSTOM = custom;
493 
494  return mode;
495 }
496 
497 #endif //MAV_MODE_H
Definition: mav_modes.h:134
Definition: mav_modes.h:147