PX4 Firmware
PX4 Autopilot Software http://px4.io
input_test.cpp
Go to the documentation of this file.
1 /****************************************************************************
2 *
3 * Copyright (c) 2016-2017 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 input_test.cpp
36  * @author Beat Küng <beat-kueng@gmx.net>
37  *
38  */
39 
40 #include "input_test.h"
41 
42 #include <math.h>
43 
44 #include <px4_platform_common/posix.h>
45 
46 
47 namespace vmount
48 {
49 
50 InputTest::InputTest(float roll_deg, float pitch_deg, float yaw_deg)
51 {
52  _angles[0] = roll_deg;
53  _angles[1] = pitch_deg;
54  _angles[2] = yaw_deg;
55 }
56 
58 {
59  return true; /* only a single-shot test (for now) */
60 }
61 
62 int InputTest::update(unsigned int timeout_ms, ControlData **control_data, bool already_active)
63 {
64  //we directly override the update() here, since we don't need the initialization from the base class
65 
67 
68  for (int i = 0; i < 3; ++i) {
70  _control_data.type_data.angle.angles[i] = _angles[i] * M_DEG_TO_RAD_F;
71 
72  _control_data.stabilize_axis[i] = false;
73  }
74 
76  *control_data = &_control_data;
77  return 0;
78 }
79 
81 {
82  return 0;
83 }
84 
86 {
87  PX4_INFO("Input: Test");
88 }
89 
90 } /* namespace vmount */
InputTest(float roll_deg, float pitch_deg, float yaw_deg)
set to a fixed angle
Definition: input_test.cpp:50
static int timeout_ms
ControlData _control_data
Definition: input.h:83
Definition: common.h:45
float _angles[3]
desired angles in [deg]
Definition: input_test.h:74
bool gimbal_shutter_retract
whether to lock the gimbal (only in RC output mode)
Definition: common.h:88
float angles[3]
attitude angles (roll, pitch, yaw) in rad, [-pi, +pi] if is_speed[i] == false
Definition: common.h:68
This defines the common API between an input and an output of the vmount driver.
Definition: common.h:55
virtual int initialize()
Definition: input_test.cpp:80
virtual int update(unsigned int timeout_ms, ControlData **control_data, bool already_active)
Wait for an input update, with a timeout.
Definition: input_test.cpp:62
bool is_speed[3]
if true, the angle is the angular speed in rad/s
Definition: common.h:70
virtual void print_status()
report status to stdout
Definition: input_test.cpp:85
control the roll, pitch & yaw angle directly
struct vmount::ControlData::TypeData::TypeAngle angle
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
bool finished()
check whether the test finished, and thus the main thread can quit
Definition: input_test.cpp:57
union vmount::ControlData::TypeData type_data