added a limit to range output
This commit is contained in:
parent
aa57fce9f4
commit
669e8e34ea
@ -111,6 +111,8 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
GSCALAR(camera_roll_gain, "CAM_R_G"),
|
GSCALAR(camera_roll_gain, "CAM_R_G"),
|
||||||
GSCALAR(stabilize_d, "STAB_D"),
|
GSCALAR(stabilize_d, "STAB_D"),
|
||||||
GSCALAR(acro_p, "ACRO_P"),
|
GSCALAR(acro_p, "ACRO_P"),
|
||||||
|
GSCALAR(axis_lock_p, "AXIS_P"),
|
||||||
|
GSCALAR(axis_enabled, "AXIS_ENABLE"),
|
||||||
|
|
||||||
// PID controller
|
// PID controller
|
||||||
//---------------
|
//---------------
|
||||||
|
@ -108,6 +108,8 @@ RC_Channel::set_pwm(int pwm)
|
|||||||
if(_type == RC_CHANNEL_RANGE){
|
if(_type == RC_CHANNEL_RANGE){
|
||||||
//Serial.print("range ");
|
//Serial.print("range ");
|
||||||
control_in = pwm_to_range();
|
control_in = pwm_to_range();
|
||||||
|
//control_in = constrain(control_in, _low, _high);
|
||||||
|
control_in = min(control_in, _high);
|
||||||
control_in = (control_in < _dead_zone) ? 0 : control_in;
|
control_in = (control_in < _dead_zone) ? 0 : control_in;
|
||||||
|
|
||||||
if (fabs(scale_output) != 1){
|
if (fabs(scale_output) != 1){
|
||||||
@ -211,9 +213,9 @@ RC_Channel::pwm_to_angle()
|
|||||||
{
|
{
|
||||||
int radio_trim_high = radio_trim + _dead_zone;
|
int radio_trim_high = radio_trim + _dead_zone;
|
||||||
int radio_trim_low = radio_trim - _dead_zone;
|
int radio_trim_low = radio_trim - _dead_zone;
|
||||||
|
|
||||||
// prevent div by 0
|
// prevent div by 0
|
||||||
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
||||||
return 0;
|
return 0;
|
||||||
|
|
||||||
if(radio_in > radio_trim_high){
|
if(radio_in > radio_trim_high){
|
||||||
@ -269,7 +271,7 @@ float
|
|||||||
RC_Channel::norm_output()
|
RC_Channel::norm_output()
|
||||||
{
|
{
|
||||||
int16_t mid = (radio_max + radio_min) / 2;
|
int16_t mid = (radio_max + radio_min) / 2;
|
||||||
|
|
||||||
if(radio_out < mid)
|
if(radio_out < mid)
|
||||||
return (float)(radio_out - mid) / (float)(mid - radio_min);
|
return (float)(radio_out - mid) / (float)(mid - radio_min);
|
||||||
else
|
else
|
||||||
|
Loading…
Reference in New Issue
Block a user