APM:Libraries
AP_Motors6DOF.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> // ArduPilot Mega Vector/Matrix math Library
8 #include <RC_Channel/RC_Channel.h> // RC Channel Library
9 #include "AP_MotorsMatrix.h"
10 
13 public:
14 
15  AP_Motors6DOF(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
16  AP_MotorsMatrix(loop_rate, speed_hz) {
18  };
19 
20  // Supported frame types
21  typedef enum {
30  } sub_frame_t;
31 
32  // Override parent
33  void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override;
34 
35  // Override parent
36  void output_min() override;
37 
38  // Map thrust input -1~1 to pwm output 1100~1900
39  int16_t calc_thrust_to_pwm(float thrust_in) const;
40 
41  // output_to_motors - sends minimum values out to the motors
42  void output_to_motors() override;
43 
44  // var_info for holding Parameter information
45  static const struct AP_Param::GroupInfo var_info[];
46 
47 protected:
48  // return current_limit as a number from 0 ~ 1 in the range throttle_min to throttle_max
49  float get_current_limit_max_throttle() override;
50 
51  //Override MotorsMatrix method
52  void add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float climb_fac, float forward_fac, float lat_fac, uint8_t testing_order);
53 
54  void output_armed_stabilizing() override;
57 
58  // Parameters
61 
62  float _throttle_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to throttle (climb/descent)
63  float _forward_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to forward/backward
64  float _lateral_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to lateral (left/right)
65 
66  // current limiting
67  float _output_limited = 1.0f;
68  float _batt_current_last = 0.0f;
69 };
AP_Motors6DOF(uint16_t loop_rate, uint16_t speed_hz=AP_MOTORS_SPEED_DEFAULT)
Definition: AP_Motors6DOF.h:15
float _forward_factor[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:63
AP_Float _forwardVerticalCouplingFactor
Definition: AP_Motors6DOF.h:60
void add_motor_raw_6dof(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, float climb_fac, float forward_fac, float lat_fac, uint8_t testing_order)
#define AP_MOTORS_SPEED_DEFAULT
float _batt_current_last
Definition: AP_Motors6DOF.h:68
float _output_limited
Definition: AP_Motors6DOF.h:67
float get_current_limit_max_throttle() override
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Motors6DOF.h:45
void output_armed_stabilizing() override
int16_t calc_thrust_to_pwm(float thrust_in) const
Motor control class for Matrixcopters.
RC_Channel manager, with EEPROM-backed storage of constants.
void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type) override
void output_to_motors() override
float _lateral_factor[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:64
Common definitions and utility routines for the ArduPilot libraries.
AP_Int8 _motor_reverse[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:59
void output_min() override
void output_armed_stabilizing_vectored()
#define AP_MOTORS_MAX_NUM_MOTORS
void output_armed_stabilizing_vectored_6dof()
float _throttle_factor[AP_MOTORS_MAX_NUM_MOTORS]
Definition: AP_Motors6DOF.h:62
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214