PX4 Firmware
PX4 Autopilot Software http://px4.io
Takeoff.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2019 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 Takeoff.cpp
36  */
37 
38 #include "Takeoff.hpp"
39 #include <mathlib/mathlib.h>
40 
41 void Takeoff::generateInitialRampValue(const float hover_thrust, float velocity_p_gain)
42 {
43  velocity_p_gain = math::max(velocity_p_gain, 0.01f);
44  _takeoff_ramp_vz_init = -hover_thrust / velocity_p_gain;
45 }
46 
47 void Takeoff::updateTakeoffState(const bool armed, const bool landed, const bool want_takeoff,
48  const float takeoff_desired_vz, const bool skip_takeoff, const hrt_abstime &now_us)
49 {
51 
52  switch (_takeoff_state) {
54  if (armed) {
56 
57  } else {
58  break;
59  }
60 
61  // FALLTHROUGH
65 
66  } else {
67  break;
68  }
69 
70  // FALLTHROUGH
72  if (want_takeoff) {
75 
76  } else {
77  break;
78  }
79 
80  // FALLTHROUGH
82  if (_takeoff_ramp_vz >= takeoff_desired_vz) {
84 
85  } else {
86  break;
87  }
88 
89  // FALLTHROUGH
91  if (landed) {
93  }
94 
95  break;
96 
97  default:
98  break;
99  }
100 
101  if (armed && skip_takeoff) {
103  }
104 
105  // TODO: need to consider free fall here
106  if (!armed) {
108  }
109 }
110 
111 float Takeoff::updateRamp(const float dt, const float takeoff_desired_vz)
112 {
114  return _takeoff_ramp_vz_init;
115  }
116 
118  if (_takeoff_ramp_time > dt) {
119  _takeoff_ramp_vz += (takeoff_desired_vz - _takeoff_ramp_vz_init) * dt / _takeoff_ramp_time;
120 
121  } else {
122  _takeoff_ramp_vz = takeoff_desired_vz;
123  }
124 
125  if (_takeoff_ramp_vz < takeoff_desired_vz) {
126  return _takeoff_ramp_vz;
127  }
128  }
129 
130  return takeoff_desired_vz;
131 }
systemlib::Hysteresis _spoolup_time_hysteresis
becomes true MPC_SPOOLUP_TIME seconds after the vehicle was armed
Definition: Takeoff.hpp:100
void generateInitialRampValue(const float hover_thrust, const float velocity_p_gain)
Calculate a vertical velocity to initialize the takeoff ramp that when passed to the velocity control...
Definition: Takeoff.cpp:41
float _takeoff_ramp_vz_init
Definition: Takeoff.hpp:97
float _takeoff_ramp_vz
Definition: Takeoff.hpp:98
float updateRamp(const float dt, const float takeoff_desired_vz)
Update and return the velocity constraint ramp value during takeoff.
Definition: Takeoff.cpp:111
void updateTakeoffState(const bool armed, const bool landed, const bool want_takeoff, const float takeoff_desired_vz, const bool skip_takeoff, const hrt_abstime &now_us)
Update the state for the takeoff.
Definition: Takeoff.cpp:47
void set_state_and_update(const bool new_state, const hrt_abstime &now_us)
Definition: hysteresis.cpp:57
bool get_state() const
Definition: hysteresis.h:60
float _takeoff_ramp_time
Definition: Takeoff.hpp:96
static struct actuator_armed_s armed
Definition: Commander.cpp:139
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
TakeoffState _takeoff_state
Definition: Takeoff.hpp:94
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
constexpr _Tp max(_Tp a, _Tp b)
Definition: Limits.hpp:60
float dt
Definition: px4io.c:73
A class handling all takeoff states and a smooth ramp up of the motors.