APM:Libraries
AP_MotorsHeli_Quad.h
Go to the documentation of this file.
1 
4 #pragma once
5 
6 #include <AP_Common/AP_Common.h>
7 #include <AP_Math/AP_Math.h>
9 
10 #include "AP_MotorsHeli.h"
11 #include "AP_MotorsHeli_RSC.h"
12 
13 // rsc function output channel
14 #define AP_MOTORS_HELI_QUAD_RSC CH_8
15 
16 // default collective min, max and midpoints for the rear swashplate
17 #define AP_MOTORS_HELI_QUAD_COLLECTIVE_MIN 1100
18 #define AP_MOTORS_HELI_QUAD_COLLECTIVE_MAX 1900
19 
20 #define AP_MOTORS_HELI_QUAD_NUM_MOTORS 4
21 
23 public:
24  // constructor
25  AP_MotorsHeli_Quad(uint16_t loop_rate,
26  uint16_t speed_hz = AP_MOTORS_HELI_SPEED_DEFAULT) :
27  AP_MotorsHeli(loop_rate, speed_hz),
29  {
31  };
32 
33  // set_update_rate - set update rate to motors
34  void set_update_rate( uint16_t speed_hz ) override;
35 
36  // output_test - spin a motor at the pwm value specified
37  void output_test(uint8_t motor_seq, int16_t pwm) override;
38 
39  // set_desired_rotor_speed - sets target rotor speed as a number from 0 ~ 1000
40  void set_desired_rotor_speed(float desired_speed) override;
41 
42  // get_estimated_rotor_speed - gets estimated rotor speed as a number from 0 ~ 1000
43  float get_main_rotor_speed() const override { return _rotor.get_rotor_speed(); }
44 
45  // get_desired_rotor_speed - gets target rotor speed as a number from 0 ~ 1000
46  float get_desired_rotor_speed() const override { return _rotor.get_rotor_speed(); }
47 
48  // rotor_speed_above_critical - return true if rotor speed is above that critical for flight
50 
51  // calculate_scalars - recalculates various scalars used
52  void calculate_scalars() override;
53 
54  // calculate_armed_scalars - recalculates scalars that can change while armed
55  void calculate_armed_scalars() override;
56 
57  // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
58  uint16_t get_motor_mask() override;
59 
60  // has_flybar - returns true if we have a mechanical flybar
61  bool has_flybar() const override { return AP_MOTORS_HELI_NOFLYBAR; }
62 
63  // supports_yaw_passthrought - returns true if we support yaw passthrough
64  bool supports_yaw_passthrough() const override { return false; }
65 
66  // servo_test - move servos through full range of movement
67  void servo_test() override;
68 
69  // var_info for holding Parameter information
70  static const struct AP_Param::GroupInfo var_info[];
71 
72 protected:
73 
74  // init_outputs
75  bool init_outputs () override;
76 
77  // update_motor_controls - sends commands to motor controllers
79 
80  // calculate_roll_pitch_collective_factors - setup rate factors
82 
83  // move_actuators - moves swash plate to attitude of parameters passed in
84  void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override;
85 
86  // objects we depend upon
87  AP_MotorsHeli_RSC _rotor; // main rotor controller
88 
89  // parameters
91 
92  // rate factors
97 };
98 
99 
#define AP_MOTORS_HELI_NOFLYBAR
Definition: AP_MotorsHeli.h:45
uint16_t get_motor_mask() override
void output_test(uint8_t motor_seq, int16_t pwm) override
void set_update_rate(uint16_t speed_hz) override
float get_desired_rotor_speed() const override
RotorControlState
void update_motor_control(RotorControlState state) override
bool has_flybar() const override
static uint16_t pwm
Definition: RCOutput.cpp:20
float _rollFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
void calculate_scalars() override
void calculate_roll_pitch_collective_factors() override
RC_Channel manager, with EEPROM-backed storage of constants.
float _pitchFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
float get_main_rotor_speed() const override
static int state
Definition: Util.cpp:20
float get_rotor_speed() const
bool init_outputs() override
float _yawFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
#define AP_MOTORS_HELI_SPEED_DEFAULT
Definition: AP_MotorsHeli.h:15
void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override
float get_critical_speed() const
Common definitions and utility routines for the ArduPilot libraries.
AP_MotorsHeli_RSC _rotor
#define AP_MOTORS_HELI_QUAD_RSC
bool supports_yaw_passthrough() const override
Motor control class for Traditional Heli.
void set_desired_rotor_speed(float desired_speed) override
bool rotor_speed_above_critical() const override
void calculate_armed_scalars() override
float _collectiveFactor[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
AP_MotorsHeli_Quad(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_HELI_SPEED_DEFAULT)
void servo_test() override
SRV_Channel * _servo[AP_MOTORS_HELI_QUAD_NUM_MOTORS]
#define AP_MOTORS_HELI_QUAD_NUM_MOTORS
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
static const struct AP_Param::GroupInfo var_info[]