APM:Libraries
AP_MotorsTailsitter.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <AP_Common/AP_Common.h>
6 #include <AP_Math/AP_Math.h>
8 #include "AP_MotorsMulticopter.h"
9 
12 public:
13 
15  AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
16 
17  // init
18  void init(motor_frame_class frame_class, motor_frame_type frame_type);
19 
20  // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
22  void set_update_rate( uint16_t speed_hz ) {}
23 
24  void output_test(uint8_t motor_seq, int16_t pwm) {}
25 
26  // output_to_motors - sends output to named servos
27  void output_to_motors();
28 
29  // return 0 motor mask
30  uint16_t get_motor_mask() { return 0; }
31 
32 protected:
33  // calculate motor outputs
35 
36  // calculated outputs
37  float _aileron; // -1..1
38  float _elevator; // -1..1
39  float _rudder; // -1..1
40  float _throttle; // 0..1
41 };
#define AP_MOTORS_SPEED_DEFAULT
static uint16_t pwm
Definition: RCOutput.cpp:20
AP_MotorsTailsitter(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
Common definitions and utility routines for the ArduPilot libraries.
void output_test(uint8_t motor_seq, int16_t pwm)
void set_update_rate(uint16_t speed_hz)
Motor control class for Multicopters.
void init(motor_frame_class frame_class, motor_frame_type frame_type)