APM:Libraries
AP_MotorsTailsitter.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_MotorsTailsitter.cpp - ArduCopter motors library for tailsitters
18  *
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Math/AP_Math.h>
23 #include "AP_MotorsTailsitter.h"
24 #include <GCS_MAVLink/GCS.h>
25 
26 extern const AP_HAL::HAL& hal;
27 
28 #define SERVO_OUTPUT_RANGE 4500
29 #define THROTTLE_RANGE 100
30 
31 // init
33 {
34  // record successful initialisation if what we setup was the desired frame_class
35  _flags.initialised_ok = (frame_class == MOTOR_FRAME_TAILSITTER);
36 }
37 
38 
40 AP_MotorsTailsitter::AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz) :
41  AP_MotorsMulticopter(loop_rate, speed_hz)
42 {
45 }
46 
48 {
49  if (!_flags.initialised_ok) {
50  return;
51  }
52  float throttle = _throttle;
53  float throttle_left = 0;
54  float throttle_right = 0;
55 
56  switch (_spool_mode) {
57  case SHUT_DOWN:
58  throttle = 0;
59  // set limits flags
60  limit.roll_pitch = true;
61  limit.yaw = true;
62  limit.throttle_lower = true;
63  limit.throttle_upper = true;
64  break;
65  case SPIN_WHEN_ARMED:
66  // sends output to motors when armed but not flying
67  throttle = constrain_float(_spin_up_ratio, 0.0f, 1.0f) * _spin_min;
68  // set limits flags
69  limit.roll_pitch = true;
70  limit.yaw = true;
71  limit.throttle_lower = true;
72  limit.throttle_upper = true;
73  break;
74  case SPOOL_UP:
75  case THROTTLE_UNLIMITED:
76  case SPOOL_DOWN: {
77  throttle = _spin_min + throttle * (1 - _spin_min);
78  throttle_left = constrain_float(throttle + _rudder*0.5, _spin_min, 1);
79  throttle_right = constrain_float(throttle - _rudder*0.5, _spin_min, 1);
80  // initialize limits flags
81  limit.roll_pitch = false;
82  limit.yaw = false;
83  limit.throttle_lower = false;
84  limit.throttle_upper = false;
85  break;
86  }
87  }
88  // outputs are setup here, and written to the HAL by the plane servos loop
93 
94  // also support differential roll with twin motors
95  SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, throttle_left*THROTTLE_RANGE);
96  SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, throttle_right*THROTTLE_RANGE);
97 
98 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
101 #endif
102 }
103 
104 // calculate outputs to the motors
106 {
107  _aileron = -_yaw_in;
109  _rudder = _roll_in;
111 
112  // sanity check throttle is above zero and below current limited throttle
113  if (_throttle <= 0.0f) {
114  _throttle = 0.0f;
115  limit.throttle_lower = true;
116  }
119  limit.throttle_upper = true;
120  }
121 
123 }
124 
secondary rudder channel
Definition: SRV_Channel.h:65
Motor control class for tailsitters.
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
Interface definition for the various Ground Control System.
struct AP_Motors::AP_Motors_flags _flags
#define SERVO_OUTPUT_RANGE
struct AP_Motors::AP_Motors_limit limit
AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
#define THROTTLE_RANGE
static void output_ch_all(void)
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
#define f(i)
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency)
spool_up_down_mode _spool_mode
float get_throttle() const
static void calc_pwm(void)
void init(motor_frame_class frame_class, motor_frame_type frame_type)