APM:Libraries
AP_MotorsCoax.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 // feedback direction
11 #define AP_MOTORS_COAX_POSITIVE 1
12 #define AP_MOTORS_COAX_NEGATIVE -1
13 
14 #define NUM_ACTUATORS 4
15 
16 #define AP_MOTORS_SINGLE_SPEED_DIGITAL_SERVOS 250 // update rate for digital servos
17 #define AP_MOTORS_SINGLE_SPEED_ANALOG_SERVOS 125 // update rate for analog servos
18 
19 #define AP_MOTORS_COAX_SERVO_INPUT_RANGE 4500 // roll or pitch input of -4500 will cause servos to their minimum (i.e. radio_min), +4500 will move them to their maximum (i.e. radio_max)
20 
23 public:
24 
26  AP_MotorsCoax(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
27  AP_MotorsMulticopter(loop_rate, speed_hz)
28  {
29  };
30 
31  // init
32  void init(motor_frame_class frame_class, motor_frame_type frame_type);
33 
34  // set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
35  void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type);
36 
37  // set update rate to motors - a value in hertz
38  void set_update_rate( uint16_t speed_hz );
39 
40  // output_test - spin a motor at the pwm value specified
41  // motor_seq is the motor's sequence number from 1 to the number of motors on the frame
42  // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
43  virtual void output_test(uint8_t motor_seq, int16_t pwm);
44 
45  // output_to_motors - sends minimum values out to the motors
46  virtual void output_to_motors();
47 
48  // get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
49  // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
50  virtual uint16_t get_motor_mask();
51 
52 protected:
53  // output - sends commands to the motors
55 
56  float _actuator_out[NUM_ACTUATORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range
59 };
virtual void output_test(uint8_t motor_seq, int16_t pwm)
#define NUM_ACTUATORS
Definition: AP_MotorsCoax.h:14
void set_update_rate(uint16_t speed_hz)
float _thrust_yt_cw
Definition: AP_MotorsCoax.h:58
float _thrust_yt_ccw
Definition: AP_MotorsCoax.h:57
#define AP_MOTORS_SPEED_DEFAULT
static uint16_t pwm
Definition: RCOutput.cpp:20
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type)
virtual void output_to_motors()
virtual uint16_t get_motor_mask()
AP_MotorsCoax(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Constructor.
Definition: AP_MotorsCoax.h:26
Common definitions and utility routines for the ArduPilot libraries.
void output_armed_stabilizing()
Motor control class for Multicopters.
void init(motor_frame_class frame_class, motor_frame_type frame_type)
float _actuator_out[NUM_ACTUATORS]
Definition: AP_MotorsCoax.h:56