Motors: configurable yaw headroom for matrix frames

This commit is contained in:
Leonard Hall 2015-02-11 21:03:39 +09:00 committed by Randy Mackay
parent 51213235b4
commit 5b0bd49ff2
4 changed files with 16 additions and 3 deletions

View File

@ -220,7 +220,7 @@ void AP_MotorsMatrix::output_armed()
// calculate amount of yaw we can fit into the throttle range
// this is always equal to or less than the requested yaw from the pilot or rate controller
yaw_allowed = min(out_max_pwm - out_best_thr_pwm, out_best_thr_pwm - out_min_pwm) - (rpy_high-rpy_low)/2;
yaw_allowed = max(yaw_allowed, AP_MOTORS_MATRIX_YAW_LOWER_LIMIT_PWM);
yaw_allowed = max(yaw_allowed, _yaw_headroom);
if (_rc_yaw.pwm_out >= 0) {
// if yawing right

View File

@ -14,8 +14,6 @@
#define AP_MOTORS_MATRIX_YAW_FACTOR_CW -1
#define AP_MOTORS_MATRIX_YAW_FACTOR_CCW 1
#define AP_MOTORS_MATRIX_YAW_LOWER_LIMIT_PWM 200
/// @class AP_MotorsMatrix
class AP_MotorsMatrix : public AP_Motors {
public:

View File

@ -69,6 +69,14 @@ const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
// @User: Standard
AP_GROUPINFO("SPIN_ARMED", 5, AP_Motors, _spin_when_armed, AP_MOTORS_SPIN_WHEN_ARMED),
// @Param: YAW_HEADROOM
// @DisplayName: Matrix Yaw Min
// @Description: Yaw control is given at least this pwm range
// @Range: 0 500
// @Units: pwm
// @User: Advanced
AP_GROUPINFO("YAW_HEADROOM", 6, AP_Motors, _yaw_headroom, AP_MOTORS_YAW_HEADROOM_DEFAULT),
AP_GROUPEND
};

View File

@ -54,6 +54,8 @@
#define AP_MOTORS_SPIN_WHEN_ARMED 70 // spin motors at this PWM value when armed
#define AP_MOTORS_YAW_HEADROOM_DEFAULT 200
// bit mask for recording which limits we have reached when outputting to motors
#define AP_MOTOR_NO_LIMITS_REACHED 0x00
#define AP_MOTOR_ROLLPITCH_LIMIT 0x01
@ -127,6 +129,9 @@ public:
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
virtual void throttle_pass_through(int16_t pwm);
// set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
virtual void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; }
// setup_throttle_curve - used to linearlise thrust output by motors
// returns true if curve is created successfully
bool setup_throttle_curve();
@ -180,6 +185,8 @@ protected:
AP_Int8 _throttle_curve_max; // throttle which produces the maximum thrust. expressed as a percentage (i.e. 0 ~ 100 ) of the full throttle range
AP_Int16 _spin_when_armed; // used to control whether the motors always spin when armed. pwm value above radio_min
AP_Int16 _yaw_headroom; // yaw control is given at least this pwm range
// internal variables
RC_Channel& _rc_roll; // roll input in from users is held in servo_out
RC_Channel& _rc_pitch; // pitch input in from users is held in servo_out