Browse Source

Copter: use set_range_in() for tuning channel

this allows channel 6 to be used for something else for output
mission-4.1.18
Andrew Tridgell 9 years ago committed by Randy Mackay
parent
commit
74883ddaeb
  1. 8
      ArduCopter/radio.cpp
  2. 2
      ArduCopter/tuning.cpp

8
ArduCopter/radio.cpp

@ -39,10 +39,10 @@ void Copter::init_rc_in() @@ -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();

2
ArduCopter/tuning.cpp

@ -17,7 +17,7 @@ void Copter::tuning() { @@ -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…
Cancel
Save