Motors: _hover_out to pct * 10 instead of pwm

This commit is contained in:
Randy Mackay 2015-02-23 11:27:51 +09:00
parent 6b7bdf64bd
commit 1a9d3125ef
2 changed files with 10 additions and 7 deletions

View File

@ -144,11 +144,10 @@ void AP_Motors::set_min_throttle(uint16_t min_throttle)
_min_throttle = (float)min_throttle * (_rc_throttle.radio_max - _rc_throttle.radio_min) / 1000.0f;
}
// set_mid_throttle - sets the mid throttle which is close to the hover throttle of the copter
// this is used to limit the amount that the stability patch will increase the throttle to give more room for roll, pitch and yaw control
void AP_Motors::set_mid_throttle(uint16_t mid_throttle)
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
int16_t AP_Motors::get_hover_throttle_as_pwm() const
{
_hover_out = _rc_throttle.radio_min + (float)(_rc_throttle.radio_max - _rc_throttle.radio_min) * mid_throttle / 1000.0f;
return (_rc_throttle.radio_min + (float)(_rc_throttle.radio_max - _rc_throttle.radio_min) * _hover_out / 1000.0f);
}
// throttle_pass_through - passes provided pwm directly to all motors - dangerous but used for initialising ESCs

View File

@ -104,9 +104,13 @@ public:
// set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
void set_min_throttle(uint16_t min_throttle);
// set_mid_throttle - sets the mid throttle which is close to the hover throttle of the copter
// set_hover_throttle - sets the mid throttle which is close to the hover throttle of the copter
// this is used to limit the amount that the stability patch will increase the throttle to give more room for roll, pitch and yaw control
void set_mid_throttle(uint16_t mid_throttle);
void set_hover_throttle(uint16_t hov_thr) { _hover_out = hov_thr; }
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
int16_t get_hover_throttle_as_pwm() const;
int16_t throttle_min() const { return _min_throttle;}
int16_t throttle_max() const { return _max_throttle;}
@ -212,7 +216,7 @@ protected:
uint16_t _speed_hz; // speed in hz to send updates to motors
int16_t _min_throttle; // the minimum throttle to be sent to the motors when they're on (prevents motors stalling while flying)
int16_t _max_throttle; // the maximum throttle to be sent to the motors (sometimes limited by slow start)
int16_t _hover_out; // the estimated hover throttle in pwm (i.e. 1000 ~ 2000). calculated from the THR_MID parameter
int16_t _hover_out; // the estimated hover throttle as pct * 10 (i.e. 0 ~ 1000)
int16_t _spin_when_armed_ramped;// equal to _spin_when_armed parameter but slowly ramped up from zero
// battery voltage compensation variables