PX4 Firmware
PX4 Autopilot Software http://px4.io
common.h
Go to the documentation of this file.
1 /****************************************************************************
2 *
3 * Copyright (c) 2016 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 
34 /**
35  * @file common.h
36  * @author Beat Küng <beat-kueng@gmx.net>
37  *
38  */
39 
40 #pragma once
41 
42 #include <stdint.h>
43 
44 
45 namespace vmount
46 {
47 
48 
49 /**
50  * @struct ControlData
51  * This defines the common API between an input and an output of the vmount driver.
52  * Each output must support the (full) set of the commands, and an input can create all
53  * or a subset of the types.
54  */
55 struct ControlData {
56 
57  enum class Type : uint8_t {
58  Neutral = 0, /**< move to neutral position */
59  Angle, /**< control the roll, pitch & yaw angle directly */
60  LonLat /**< control via lon, lat */
61  //TODO: add more, like smooth curve, ... ?
62  };
63 
65 
66  union TypeData {
67  struct TypeAngle {
68  float angles[3]; /**< attitude angles (roll, pitch, yaw) in rad, [-pi, +pi] if is_speed[i] == false */
69 
70  bool is_speed[3]; /**< if true, the angle is the angular speed in rad/s */
71  } angle;
72 
73  struct TypeLonLat {
74  double lon; /**< longitude in [deg] */
75  double lat; /**< latitude in [deg] */
76  float altitude; /**< altitude in [m] */
77  float roll_angle; /**< roll is set to a fixed angle. Set to 0 for level horizon [rad] */
78  float pitch_angle_offset; /**< angular offset for pitch [rad] */
79  float yaw_angle_offset; /**< angular offset for yaw [rad] */
80  float pitch_fixed_angle; /**< ignored if < -pi, otherwise use a fixed pitch angle instead of the altitude */
81  } lonlat;
82  } type_data;
83 
84 
85  bool stabilize_axis[3] = { false, false, false }; /**< whether the vmount driver should stabilize an axis
86  (if the output supports it, this can also be done externally) */
87 
88  bool gimbal_shutter_retract = false; /**< whether to lock the gimbal (only in RC output mode) */
89 
90 };
91 
92 
93 } /* namespace vmount */
float yaw_angle_offset
angular offset for yaw [rad]
Definition: common.h:79
double lon
longitude in [deg]
Definition: common.h:74
float pitch_angle_offset
angular offset for pitch [rad]
Definition: common.h:78
float pitch_fixed_angle
ignored if < -pi, otherwise use a fixed pitch angle instead of the altitude
Definition: common.h:80
float altitude
altitude in [m]
Definition: common.h:76
move to neutral position
Definition: common.h:45
float roll_angle
roll is set to a fixed angle.
Definition: common.h:77
bool gimbal_shutter_retract
whether to lock the gimbal (only in RC output mode)
Definition: common.h:88
double lat
latitude in [deg]
Definition: common.h:75
This defines the common API between an input and an output of the vmount driver.
Definition: common.h:55
control the roll, pitch & yaw angle directly
bool stabilize_axis[3]
whether the vmount driver should stabilize an axis (if the output supports it, this can also be done ...
Definition: common.h:85
union vmount::ControlData::TypeData type_data