mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
RC_Channel: Remove unneeded interfaces
This commit is contained in:
parent
c85f8c7bf5
commit
95eda5d9b7
@ -161,26 +161,6 @@ int16_t RC_Channel::get_control_mid() const
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// ------------------------------------------
|
|
||||||
|
|
||||||
void RC_Channel::load_eeprom(void)
|
|
||||||
{
|
|
||||||
radio_min.load();
|
|
||||||
radio_trim.load();
|
|
||||||
radio_max.load();
|
|
||||||
reversed.load();
|
|
||||||
dead_zone.load();
|
|
||||||
}
|
|
||||||
|
|
||||||
void RC_Channel::save_eeprom(void)
|
|
||||||
{
|
|
||||||
radio_min.save();
|
|
||||||
radio_trim.save();
|
|
||||||
radio_max.save();
|
|
||||||
reversed.save();
|
|
||||||
dead_zone.save();
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return an "angle in centidegrees" (normally -4500 to 4500) from
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
||||||
the current radio_in value using the specified dead_zone
|
the current radio_in value using the specified dead_zone
|
||||||
|
@ -26,11 +26,6 @@ public:
|
|||||||
RC_CHANNEL_LIMIT_MAX
|
RC_CHANNEL_LIMIT_MAX
|
||||||
};
|
};
|
||||||
|
|
||||||
// startup
|
|
||||||
void load_eeprom(void);
|
|
||||||
void save_eeprom(void);
|
|
||||||
void save_trim(void);
|
|
||||||
|
|
||||||
// setup the control preferences
|
// setup the control preferences
|
||||||
void set_range(uint16_t high);
|
void set_range(uint16_t high);
|
||||||
void set_angle(uint16_t angle);
|
void set_angle(uint16_t angle);
|
||||||
|
Loading…
Reference in New Issue
Block a user