2012-04-02 05:26:37 -03:00
|
|
|
/// @file AP_MotorsMatrix.h
|
|
|
|
/// @brief Motor control class for Matrixcopters
|
2016-02-17 21:25:38 -04:00
|
|
|
#pragma once
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2015-08-11 03:28:44 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Math/AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
|
|
|
#include <RC_Channel/RC_Channel.h> // RC Channel Library
|
2015-07-15 04:57:45 -03:00
|
|
|
#include "AP_MotorsMulticopter.h"
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2013-04-25 05:52:19 -03:00
|
|
|
#define AP_MOTORS_MATRIX_YAW_FACTOR_CW -1
|
|
|
|
#define AP_MOTORS_MATRIX_YAW_FACTOR_CCW 1
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// @class AP_MotorsMatrix
|
2015-07-15 04:57:45 -03:00
|
|
|
class AP_MotorsMatrix : public AP_MotorsMulticopter {
|
2012-08-17 03:20:27 -03:00
|
|
|
public:
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
/// Constructor
|
2022-12-06 21:03:36 -04:00
|
|
|
AP_MotorsMatrix(uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT) :
|
|
|
|
AP_MotorsMulticopter(speed_hz)
|
2021-01-19 12:44:02 -04:00
|
|
|
{
|
|
|
|
if (_singleton != nullptr) {
|
|
|
|
AP_HAL::panic("AP_MotorsMatrix must be singleton");
|
|
|
|
}
|
|
|
|
_singleton = this;
|
|
|
|
};
|
|
|
|
|
|
|
|
// get singleton instance
|
|
|
|
static AP_MotorsMatrix *get_singleton() {
|
|
|
|
return _singleton;
|
|
|
|
}
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
// init
|
2021-06-19 15:13:36 -03:00
|
|
|
virtual void init(motor_frame_class frame_class, motor_frame_type frame_type) override;
|
2016-12-14 01:46:42 -04:00
|
|
|
|
2021-11-15 01:08:29 -04:00
|
|
|
#if AP_SCRIPTING_ENABLED
|
2021-01-19 12:44:02 -04:00
|
|
|
// Init to be called from scripting
|
2021-01-26 15:03:53 -04:00
|
|
|
virtual bool init(uint8_t expected_num_motors);
|
2021-05-16 19:45:22 -03:00
|
|
|
|
|
|
|
// Set throttle factor from scripting
|
|
|
|
bool set_throttle_factor(int8_t motor_num, float throttle_factor);
|
|
|
|
|
2021-11-15 01:08:29 -04:00
|
|
|
#endif // AP_SCRIPTING_ENABLED
|
2021-01-19 12:44:02 -04:00
|
|
|
|
2016-12-14 01:46:42 -04:00
|
|
|
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
|
2018-11-07 07:00:51 -04:00
|
|
|
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override;
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2012-09-13 09:31:13 -03:00
|
|
|
// set update rate to motors - a value in hertz
|
2012-08-17 03:20:27 -03:00
|
|
|
// you must have setup_motors before calling this
|
2018-11-07 07:00:51 -04:00
|
|
|
void set_update_rate(uint16_t speed_hz) override;
|
2012-04-02 05:26:37 -03:00
|
|
|
|
2018-04-19 16:12:28 -03:00
|
|
|
// output_test_num - spin a motor connected to the specified output channel
|
|
|
|
// (should only be performed during testing)
|
|
|
|
// If a motor output channel is remapped, the mapped channel is used.
|
|
|
|
// Returns true if motor output is set, false otherwise
|
|
|
|
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
|
|
|
bool output_test_num(uint8_t motor, int16_t pwm);
|
|
|
|
|
2016-01-18 01:18:34 -04:00
|
|
|
// output_to_motors - sends minimum values out to the motors
|
2021-06-19 15:13:36 -03:00
|
|
|
virtual void output_to_motors() override;
|
2016-01-18 01:18:34 -04:00
|
|
|
|
2014-07-26 04:29:48 -03:00
|
|
|
// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
|
|
|
|
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
2021-12-10 12:45:20 -04:00
|
|
|
uint32_t get_motor_mask() override;
|
2014-07-26 04:29:48 -03:00
|
|
|
|
2018-08-12 11:19:20 -03:00
|
|
|
// return number of motor that has failed. Should only be called if get_thrust_boost() returns true
|
2018-11-07 07:00:51 -04:00
|
|
|
uint8_t get_lost_motor() const override { return _motor_lost_index; }
|
2018-08-12 11:19:20 -03:00
|
|
|
|
2018-12-29 11:43:58 -04:00
|
|
|
// return the roll factor of any motor, this is used for tilt rotors and tail sitters
|
|
|
|
// using copter motors for forward flight
|
|
|
|
float get_roll_factor(uint8_t i) override { return _roll_factor[i]; }
|
2021-07-27 16:51:00 -03:00
|
|
|
// return the pitch factor of any motor
|
|
|
|
float get_pitch_factor(uint8_t i) override { return _pitch_factor[i]; }
|
2018-12-29 11:43:58 -04:00
|
|
|
|
2020-12-12 00:45:57 -04:00
|
|
|
// disable the use of motor torque to control yaw. Used when an external mechanism such
|
|
|
|
// as vectoring is used for yaw control
|
|
|
|
void disable_yaw_torque(void) override;
|
|
|
|
|
2021-01-19 12:44:02 -04:00
|
|
|
// add_motor using raw roll, pitch, throttle and yaw factors
|
2021-05-16 19:45:22 -03:00
|
|
|
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order, float throttle_factor = 1.0f);
|
2021-01-19 12:44:02 -04:00
|
|
|
|
2021-08-30 23:43:08 -03:00
|
|
|
// same structure, but with floats.
|
|
|
|
struct MotorDef {
|
|
|
|
float angle_degrees;
|
|
|
|
float yaw_factor;
|
|
|
|
uint8_t testing_order;
|
|
|
|
};
|
2021-08-30 07:54:02 -03:00
|
|
|
|
|
|
|
// method to add many motors specified in a structure:
|
2021-09-01 04:46:05 -03:00
|
|
|
void add_motors(const struct MotorDef *motors, uint8_t num_motors);
|
2021-08-30 07:54:02 -03:00
|
|
|
|
2021-08-31 00:15:18 -03:00
|
|
|
// structure used for initialising motors that add have separate
|
|
|
|
// roll/pitch/yaw factors. Note that this does *not* include
|
|
|
|
// the final parameter for the add_motor_raw call - throttle
|
|
|
|
// factor as that is only used in the scripting binding, not in
|
|
|
|
// the static motors at the moment.
|
|
|
|
struct MotorDefRaw {
|
|
|
|
float roll_fac;
|
|
|
|
float pitch_fac;
|
|
|
|
float yaw_fac;
|
|
|
|
uint8_t testing_order;
|
|
|
|
};
|
|
|
|
void add_motors_raw(const struct MotorDefRaw *motors, uint8_t num_motors);
|
|
|
|
|
2023-02-18 15:25:53 -04:00
|
|
|
// pull values direct, (examples only)
|
|
|
|
float get_thrust_rpyt_out(uint8_t i) const;
|
|
|
|
bool get_factors(uint8_t i, float &roll, float &pitch, float &yaw, float &throttle, uint8_t &testing_order) const;
|
|
|
|
|
2012-04-02 05:26:37 -03:00
|
|
|
protected:
|
2012-08-17 03:20:27 -03:00
|
|
|
// output - sends commands to the motors
|
2018-11-07 07:00:51 -04:00
|
|
|
void output_armed_stabilizing() override;
|
2012-08-17 03:20:27 -03:00
|
|
|
|
2018-08-12 11:19:20 -03:00
|
|
|
// check for failed motor
|
|
|
|
void check_for_failed_motor(float throttle_thrust_best);
|
|
|
|
|
2016-12-14 01:34:15 -04:00
|
|
|
// add_motor using just position and yaw_factor (or prop direction)
|
|
|
|
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);
|
|
|
|
|
|
|
|
// add_motor using separate roll and pitch factors (for asymmetrical frames) and prop direction
|
|
|
|
void add_motor(int8_t motor_num, float roll_factor_in_degrees, float pitch_factor_in_degrees, float yaw_factor, uint8_t testing_order);
|
|
|
|
|
|
|
|
// remove_motor
|
|
|
|
void remove_motor(int8_t motor_num);
|
|
|
|
|
2016-12-14 01:46:42 -04:00
|
|
|
// configures the motors for the defined frame_class and frame_type
|
2016-01-01 18:20:32 -04:00
|
|
|
virtual void setup_motors(motor_frame_class frame_class, motor_frame_type frame_type);
|
2016-12-14 01:46:42 -04:00
|
|
|
|
2016-02-04 07:45:49 -04:00
|
|
|
// normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
|
|
|
|
void normalise_rpy_factors();
|
|
|
|
|
2016-05-01 19:00:45 -03:00
|
|
|
// call vehicle supplied thrust compensation if set
|
|
|
|
void thrust_compensation(void) override;
|
2018-08-21 01:15:52 -03:00
|
|
|
|
2022-01-01 11:55:34 -04:00
|
|
|
const char* _get_frame_string() const override { return _frame_class_string; }
|
|
|
|
const char* get_type_string() const override { return _frame_type_string; }
|
|
|
|
|
2022-01-27 11:37:06 -04:00
|
|
|
// output_test_seq - spin a motor at the pwm value specified
|
|
|
|
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
|
|
|
|
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
|
|
|
virtual void _output_test_seq(uint8_t motor_seq, int16_t pwm) override;
|
|
|
|
|
2012-08-17 03:20:27 -03:00
|
|
|
float _roll_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to roll
|
|
|
|
float _pitch_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to pitch
|
|
|
|
float _yaw_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to yaw (normally 1 or -1)
|
2021-05-16 19:45:22 -03:00
|
|
|
float _throttle_factor[AP_MOTORS_MAX_NUM_MOTORS]; // each motors contribution to throttle 0~1
|
2015-12-03 01:48:35 -04:00
|
|
|
float _thrust_rpyt_out[AP_MOTORS_MAX_NUM_MOTORS]; // combined roll, pitch, yaw and throttle outputs to motors in 0~1 range
|
2013-05-14 06:03:34 -03:00
|
|
|
uint8_t _test_order[AP_MOTORS_MAX_NUM_MOTORS]; // order of the motors in the test sequence
|
2018-08-12 11:19:20 -03:00
|
|
|
|
|
|
|
// motor failure handling
|
|
|
|
float _thrust_rpyt_out_filt[AP_MOTORS_MAX_NUM_MOTORS]; // filtered thrust outputs with 1 second time constant
|
|
|
|
uint8_t _motor_lost_index; // index number of the lost motor
|
2021-01-19 12:44:02 -04:00
|
|
|
|
2020-11-05 15:59:35 -04:00
|
|
|
motor_frame_class _active_frame_class; // active frame class (i.e. quad, hexa, octa, etc)
|
|
|
|
motor_frame_type _active_frame_type; // active frame type (i.e. plus, x, v, etc)
|
|
|
|
|
|
|
|
const char* _frame_class_string = ""; // string representation of frame class
|
|
|
|
const char* _frame_type_string = ""; // string representation of frame type
|
2022-08-02 18:15:44 -03:00
|
|
|
|
2021-01-19 12:44:02 -04:00
|
|
|
private:
|
2023-02-07 14:26:06 -04:00
|
|
|
|
|
|
|
// helper to return value scaled between boost and normal based on the value of _thrust_boost_ratio
|
|
|
|
float boost_ratio(float boost_value, float normal_value) const;
|
|
|
|
|
2022-08-02 18:15:44 -03:00
|
|
|
// setup motors matrix
|
|
|
|
bool setup_quad_matrix(motor_frame_type frame_type);
|
|
|
|
bool setup_hexa_matrix(motor_frame_type frame_type);
|
|
|
|
bool setup_octa_matrix(motor_frame_type frame_type);
|
|
|
|
bool setup_deca_matrix(motor_frame_type frame_type);
|
|
|
|
bool setup_dodecahexa_matrix(motor_frame_type frame_type);
|
|
|
|
bool setup_y6_matrix(motor_frame_type frame_type);
|
|
|
|
bool setup_octaquad_matrix(motor_frame_type frame_type);
|
|
|
|
|
2021-01-19 12:44:02 -04:00
|
|
|
static AP_MotorsMatrix *_singleton;
|
2012-08-17 03:20:27 -03:00
|
|
|
};
|