mirror of https://github.com/ArduPilot/ardupilot
RC_Channel Dead zone
Added APVar dead_zone to the RC_Channel library so you could edit it in the Mission planner Made CH filtering off by default.
This commit is contained in:
parent
6fd7c1dcda
commit
76bf784f8c
|
@ -139,8 +139,12 @@ static void auto_trim()
|
||||||
led_mode = NORMAL_LEDS;
|
led_mode = NORMAL_LEDS;
|
||||||
clear_leds();
|
clear_leds();
|
||||||
imu.save();
|
imu.save();
|
||||||
|
|
||||||
//Serial.println("Done");
|
//Serial.println("Done");
|
||||||
auto_level_counter = 0;
|
auto_level_counter = 0;
|
||||||
|
|
||||||
|
// set TC
|
||||||
|
init_throttle_cruise();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -4,6 +4,13 @@
|
||||||
// ----------------------------------------------------------------------------
|
// ----------------------------------------------------------------------------
|
||||||
static byte failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
static byte failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
||||||
|
|
||||||
|
static void default_dead_zones()
|
||||||
|
{
|
||||||
|
g.rc_1.set_dead_zone(60);
|
||||||
|
g.rc_2.set_dead_zone(60);
|
||||||
|
g.rc_3.set_dead_zone(60);
|
||||||
|
g.rc_4.set_dead_zone(200);
|
||||||
|
}
|
||||||
|
|
||||||
static void init_rc_in()
|
static void init_rc_in()
|
||||||
{
|
{
|
||||||
|
@ -29,14 +36,9 @@ static void init_rc_in()
|
||||||
g.rc_4.dead_zone = 300;
|
g.rc_4.dead_zone = 300;
|
||||||
*/
|
*/
|
||||||
|
|
||||||
g.rc_1.set_dead_zone(60);
|
|
||||||
g.rc_2.set_dead_zone(60);
|
|
||||||
g.rc_3.set_dead_zone(60);
|
|
||||||
g.rc_4.set_dead_zone(200);
|
|
||||||
|
|
||||||
//set auxiliary ranges
|
//set auxiliary ranges
|
||||||
g.rc_5.set_range(0,1000);
|
g.rc_5.set_range(0,1000);
|
||||||
g.rc_5.set_filter(false);
|
|
||||||
g.rc_6.set_range(0,1000);
|
g.rc_6.set_range(0,1000);
|
||||||
g.rc_7.set_range(0,1000);
|
g.rc_7.set_range(0,1000);
|
||||||
g.rc_8.set_range(0,1000);
|
g.rc_8.set_range(0,1000);
|
||||||
|
|
|
@ -38,7 +38,7 @@ RC_Channel::set_angle(int angle)
|
||||||
void
|
void
|
||||||
RC_Channel::set_dead_zone(int dzone)
|
RC_Channel::set_dead_zone(int dzone)
|
||||||
{
|
{
|
||||||
_dead_zone = abs(dzone >>1);
|
_dead_zone.set_and_save(abs(dzone >>1));
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
|
|
|
@ -26,9 +26,10 @@ class RC_Channel{
|
||||||
radio_trim(&_group, 1, 1500, name ? PSTR("TRIM") : 0),
|
radio_trim(&_group, 1, 1500, name ? PSTR("TRIM") : 0),
|
||||||
radio_max (&_group, 2, 1900, name ? PSTR("MAX") : 0),
|
radio_max (&_group, 2, 1900, name ? PSTR("MAX") : 0),
|
||||||
_high(1),
|
_high(1),
|
||||||
_filter(true),
|
_filter(false),
|
||||||
_reverse (&_group, 3, 1, name ? PSTR("REV") : 0),
|
_reverse (&_group, 3, 1, name ? PSTR("REV") : 0),
|
||||||
_dead_zone(0),
|
_dead_zone (&_group, 4, 0, name ? PSTR("DZ") : 0),
|
||||||
|
//_dead_zone(0),
|
||||||
scale_output(1.0)
|
scale_output(1.0)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
@ -97,7 +98,8 @@ class RC_Channel{
|
||||||
bool _filter;
|
bool _filter;
|
||||||
AP_Int8 _reverse;
|
AP_Int8 _reverse;
|
||||||
|
|
||||||
int16_t _dead_zone; // used to keep noise down and create a dead zone.
|
AP_Int16 _dead_zone;
|
||||||
|
//int16_t _dead_zone; // used to keep noise down and create a dead zone.
|
||||||
uint8_t _type;
|
uint8_t _type;
|
||||||
int16_t _high;
|
int16_t _high;
|
||||||
int16_t _low;
|
int16_t _low;
|
||||||
|
|
Loading…
Reference in New Issue