APM:Libraries
AP_MotorsTri.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> // ArduPilot Mega Vector/Matrix math Library
8 #include "AP_MotorsMulticopter.h"
9 
10 // tail servo uses channel 7
11 #define AP_MOTORS_CH_TRI_YAW CH_7
12 
13 #define AP_MOTORS_TRI_SERVO_RANGE_DEG_MIN 5 // minimum angle movement of tail servo in degrees
14 #define AP_MOTORS_TRI_SERVO_RANGE_DEG_MAX 80 // maximum angle movement of tail servo in degrees
15 
18 public:
19 
21  AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
22  AP_MotorsMulticopter(loop_rate, speed_hz)
23  {
24  };
25 
26  // init
27  void init(motor_frame_class frame_class, motor_frame_type frame_type);
28 
29  // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
30  void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type);
31 
32  // set update rate to motors - a value in hertz
33  void set_update_rate( uint16_t speed_hz );
34 
35  // output_test - spin a motor at the pwm value specified
36  // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
37  // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
38  virtual void output_test(uint8_t motor_seq, int16_t pwm);
39 
40  // output_to_motors - sends minimum values out to the motors
41  virtual void output_to_motors();
42 
43  // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
44  // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
45  virtual uint16_t get_motor_mask();
46 
47  // output a thrust to all motors that match a given motor
48  // mask. This is used to control tiltrotor motors in forward
49  // flight. Thrust is in the range 0 to 1
50  void output_motor_mask(float thrust, uint8_t mask) override;
51 
52 protected:
53  // output - sends commands to the motors
55 
56  // call vehicle supplied thrust compensation if set
57  void thrust_compensation(void) override;
58 
59  // calc_yaw_radio_output - calculate final radio output for yaw channel
60  int16_t calc_yaw_radio_output(float yaw_input, float yaw_input_max); // calculate radio output for yaw servo, typically in range of 1100-1900
61 
62  // parameters
63 
64  SRV_Channel *_yaw_servo; // yaw output channel
65  float _pivot_angle; // Angle of yaw pivot
67  float _thrust_rear;
68  float _thrust_left;
69 };
float _thrust_right
Definition: AP_MotorsTri.h:66
virtual void output_test(uint8_t motor_seq, int16_t pwm)
AP_MotorsTri(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
Definition: AP_MotorsTri.h:21
void output_armed_stabilizing()
#define AP_MOTORS_SPEED_DEFAULT
void thrust_compensation(void) override
static uint16_t pwm
Definition: RCOutput.cpp:20
float _thrust_rear
Definition: AP_MotorsTri.h:67
int16_t calc_yaw_radio_output(float yaw_input, float yaw_input_max)
SRV_Channel * _yaw_servo
Definition: AP_MotorsTri.h:64
float _pivot_angle
Definition: AP_MotorsTri.h:65
void init(motor_frame_class frame_class, motor_frame_type frame_type)
Common definitions and utility routines for the ArduPilot libraries.
virtual uint16_t get_motor_mask()
float _thrust_left
Definition: AP_MotorsTri.h:68
Motor control class for Multicopters.
void output_motor_mask(float thrust, uint8_t mask) override
virtual void output_to_motors()
void set_update_rate(uint16_t speed_hz)
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)