Main Page
Related Pages
Modules
Namespaces
Classes
Files
Examples
File List
File Members
include
mavros
px4_custom_mode.h
Go to the documentation of this file.
1
/****************************************************************************
2
*
3
* Copyright (c) 2013-2015 PX4 Development Team. 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
7
* are met:
8
*
9
* 1. Redistributions of source code must retain the above copyright
10
* notice, this list of conditions and the following disclaimer.
11
* 2. Redistributions in binary form must reproduce the above copyright
12
* notice, this list of conditions and the following disclaimer in
13
* the documentation and/or other materials provided with the
14
* distribution.
15
* 3. Neither the name PX4 nor the names of its contributors may be
16
* used to endorse or promote products derived from this software
17
* without specific prior written permission.
18
*
19
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30
* POSSIBILITY OF SUCH DAMAGE.
31
*
32
****************************************************************************/
33
44
#pragma once
45
46
//#include <stdint.h>
47
48
namespace
px4
{
55
union
custom_mode
{
56
enum
MAIN_MODE
: uint8_t {
57
MAIN_MODE_MANUAL
= 1,
58
MAIN_MODE_ALTCTL
,
59
MAIN_MODE_POSCTL
,
60
MAIN_MODE_AUTO
,
61
MAIN_MODE_ACRO
,
62
MAIN_MODE_OFFBOARD
,
63
MAIN_MODE_STABILIZED
,
64
MAIN_MODE_RATTITUDE
65
};
66
67
enum
SUB_MODE_AUTO
: uint8_t {
68
SUB_MODE_AUTO_READY
= 1,
69
SUB_MODE_AUTO_TAKEOFF
,
70
SUB_MODE_AUTO_LOITER
,
71
SUB_MODE_AUTO_MISSION
,
72
SUB_MODE_AUTO_RTL
,
73
SUB_MODE_AUTO_LAND
,
74
SUB_MODE_AUTO_RTGS
,
75
SUB_MODE_AUTO_FOLLOW_TARGET
,
76
SUB_MODE_AUTO_PRECLAND
77
};
78
79
struct
{
80
uint16_t
reserved
;
81
uint8_t
main_mode
;
82
uint8_t
sub_mode
;
83
};
84
uint32_t
data
;
85
float
data_float
;
86
87
custom_mode
() : data(0)
88
{ }
89
90
explicit
custom_mode
(uint32_t val) : data(val)
91
{ }
92
93
constexpr
custom_mode
(uint8_t mm, uint8_t sm) :
94
reserved
(0),
95
main_mode
(mm),
96
sub_mode
(sm)
97
{ }
98
};
99
107
constexpr uint32_t
define_mode
(
enum
custom_mode::MAIN_MODE
mm, uint8_t sm = 0) {
108
return
custom_mode
(mm, sm).data;
109
}
110
119
constexpr uint32_t
define_mode_auto
(
enum
custom_mode::SUB_MODE_AUTO
sm) {
120
return
define_mode
(
custom_mode::MAIN_MODE_AUTO
, sm);
121
}
122
};
// namespace px4
px4::custom_mode::MAIN_MODE_OFFBOARD
Definition:
px4_custom_mode.h:62
px4::custom_mode::SUB_MODE_AUTO_READY
Definition:
px4_custom_mode.h:68
px4::custom_mode::data
uint32_t data
Definition:
px4_custom_mode.h:84
px4::custom_mode::SUB_MODE_AUTO_FOLLOW_TARGET
Definition:
px4_custom_mode.h:75
px4::custom_mode::SUB_MODE_AUTO_MISSION
Definition:
px4_custom_mode.h:71
px4::custom_mode::SUB_MODE_AUTO
SUB_MODE_AUTO
Definition:
px4_custom_mode.h:67
px4::custom_mode::custom_mode
custom_mode(uint32_t val)
Definition:
px4_custom_mode.h:90
px4::custom_mode::MAIN_MODE_ALTCTL
Definition:
px4_custom_mode.h:58
px4::custom_mode::SUB_MODE_AUTO_RTL
Definition:
px4_custom_mode.h:72
px4::custom_mode::SUB_MODE_AUTO_TAKEOFF
Definition:
px4_custom_mode.h:69
px4::custom_mode::custom_mode
constexpr custom_mode(uint8_t mm, uint8_t sm)
Definition:
px4_custom_mode.h:93
px4::custom_mode::MAIN_MODE_RATTITUDE
Definition:
px4_custom_mode.h:64
px4::custom_mode::MAIN_MODE_ACRO
Definition:
px4_custom_mode.h:61
px4::custom_mode::reserved
uint16_t reserved
Definition:
px4_custom_mode.h:80
px4::custom_mode::data_float
float data_float
Definition:
px4_custom_mode.h:85
px4::custom_mode::main_mode
uint8_t main_mode
Definition:
px4_custom_mode.h:81
px4::define_mode_auto
constexpr uint32_t define_mode_auto(enum custom_mode::SUB_MODE_AUTO sm)
helper function to define auto mode as uint32_t constant
Definition:
px4_custom_mode.h:119
px4::custom_mode::MAIN_MODE_POSCTL
Definition:
px4_custom_mode.h:59
px4::custom_mode::MAIN_MODE_AUTO
Definition:
px4_custom_mode.h:60
px4::custom_mode::MAIN_MODE
MAIN_MODE
Definition:
px4_custom_mode.h:56
px4::custom_mode::MAIN_MODE_STABILIZED
Definition:
px4_custom_mode.h:63
px4::custom_mode
PX4 custom mode.
Definition:
px4_custom_mode.h:55
px4::custom_mode::MAIN_MODE_MANUAL
Definition:
px4_custom_mode.h:57
px4::custom_mode::SUB_MODE_AUTO_RTGS
Definition:
px4_custom_mode.h:74
px4
Definition:
px4_custom_mode.h:48
px4::custom_mode::SUB_MODE_AUTO_LOITER
Definition:
px4_custom_mode.h:70
px4::custom_mode::SUB_MODE_AUTO_LAND
Definition:
px4_custom_mode.h:73
px4::custom_mode::SUB_MODE_AUTO_PRECLAND
Definition:
px4_custom_mode.h:76
px4::custom_mode::sub_mode
uint8_t sub_mode
Definition:
px4_custom_mode.h:82
px4::define_mode
constexpr uint32_t define_mode(enum custom_mode::MAIN_MODE mm, uint8_t sm=0)
helper function to define any mode as uint32_t constant
Definition:
px4_custom_mode.h:107
px4::custom_mode::custom_mode
custom_mode()
Definition:
px4_custom_mode.h:87
mavros
Author(s): Vladimir Ermakov
autogenerated on Tue Jun 1 2021 02:36:26