mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: calc_roll_pwm based on throttle pwm range
This commit is contained in:
parent
ca915d9928
commit
1a583c5382
|
@ -350,6 +350,7 @@ void AP_MotorsMulticopter::set_throttle_range(uint16_t min_throttle, int16_t rad
|
|||
_throttle_radio_min = radio_min;
|
||||
_throttle_radio_max = radio_max;
|
||||
_throttle_pwm_scalar = (_throttle_radio_max - _throttle_radio_min) / 1000.0f;
|
||||
_rpy_pwm_scalar = (_throttle_radio_max - (_throttle_radio_min + _min_throttle)) / 9000.0f;
|
||||
_min_throttle = (float)min_throttle * _throttle_pwm_scalar;
|
||||
}
|
||||
|
||||
|
|
|
@ -131,9 +131,9 @@ protected:
|
|||
// RPY channels typically +/-45 degrees servo travel between +/-400 PWM
|
||||
// Throttle channel typically 0-1000 range converts to 1100-1900 PWM for final output signal to motors
|
||||
// ToDo: this should all be handled as floats +/- 1.0 instead of PWM and fake angle ranges
|
||||
int16_t calc_roll_pwm() { return (_roll_control_input / 11.25f);}
|
||||
int16_t calc_pitch_pwm() { return (_pitch_control_input / 11.25f);}
|
||||
int16_t calc_yaw_pwm() { return (_yaw_control_input / 11.25f);}
|
||||
float calc_roll_pwm() { return (_roll_control_input * _rpy_pwm_scalar); }
|
||||
float calc_pitch_pwm() { return (_pitch_control_input * _rpy_pwm_scalar); }
|
||||
float calc_yaw_pwm() { return (_yaw_control_input * _rpy_pwm_scalar); }
|
||||
int16_t calc_throttle_radio_output() { return (_throttle_control_input * _throttle_pwm_scalar) + _throttle_radio_min;}
|
||||
|
||||
// flag bitmask
|
||||
|
|
|
@ -34,6 +34,7 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
|||
_throttle_control_input(0.0f),
|
||||
_yaw_control_input(0.0f),
|
||||
_throttle_pwm_scalar(1.0f),
|
||||
_rpy_pwm_scalar(0.074f),
|
||||
_loop_rate(loop_rate),
|
||||
_speed_hz(speed_hz),
|
||||
_throttle_radio_min(1100),
|
||||
|
|
|
@ -153,6 +153,7 @@ protected:
|
|||
float _throttle_control_input; // desired throttle (thrust) control from attitude controller, 0-1000
|
||||
float _yaw_control_input; // desired yaw control from attitude controller, +/- 4500
|
||||
float _throttle_pwm_scalar; // scalar used to convert throttle channel pwm range into 0-1000 range, ~0.8 - 1.0
|
||||
float _rpy_pwm_scalar; // scaler used to convert roll, pitch, yaw inputs to pwm range
|
||||
uint16_t _loop_rate; // rate at which output() function is called (normally 400hz)
|
||||
uint16_t _speed_hz; // speed in hz to send updates to motors
|
||||
int16_t _throttle_radio_min; // minimum radio channel pwm
|
||||
|
|
Loading…
Reference in New Issue