Copter: use set_range_in() for tuning channel
this allows channel 6 to be used for something else for output
This commit is contained in:
parent
48b774bc63
commit
74883ddaeb
@ -39,10 +39,10 @@ void Copter::init_rc_in()
|
||||
channel_yaw->set_type(RC_CHANNEL_TYPE_ANGLE_RAW);
|
||||
|
||||
//set auxiliary servo ranges
|
||||
g.rc_5.set_range(0,1000);
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.rc_7.set_range(0,1000);
|
||||
g.rc_8.set_range(0,1000);
|
||||
g.rc_5.set_range_in(0,1000);
|
||||
g.rc_6.set_range_in(0,1000);
|
||||
g.rc_7.set_range_in(0,1000);
|
||||
g.rc_8.set_range_in(0,1000);
|
||||
|
||||
// set default dead zones
|
||||
default_dead_zones();
|
||||
|
@ -17,7 +17,7 @@ void Copter::tuning() {
|
||||
}
|
||||
|
||||
// set tuning range and then get new value
|
||||
g.rc_6.set_range(g.radio_tuning_low,g.radio_tuning_high);
|
||||
g.rc_6.set_range_in(g.radio_tuning_low,g.radio_tuning_high);
|
||||
float tuning_value = (float)g.rc_6.control_in / 1000.0f;
|
||||
// Tuning Value should never be outside the bounds of the specified low and high value
|
||||
tuning_value = constrain_float(tuning_value, g.radio_tuning_low/1000.0f, g.radio_tuning_high/1000.0f);
|
||||
|
Loading…
Reference in New Issue
Block a user