mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
RC_Channel: added set_and_save_trim()
This commit is contained in:
parent
cde4afd28e
commit
b50ab75f4c
@ -95,6 +95,8 @@ public:
|
|||||||
void set_radio_trim(int16_t val) { radio_trim.set(val);}
|
void set_radio_trim(int16_t val) { radio_trim.set(val);}
|
||||||
void save_radio_trim() { radio_trim.save();}
|
void save_radio_trim() { radio_trim.save();}
|
||||||
|
|
||||||
|
void set_and_save_trim() { radio_trim.set_and_save(radio_in);}
|
||||||
|
|
||||||
bool min_max_configured() const
|
bool min_max_configured() const
|
||||||
{
|
{
|
||||||
return radio_min.configured() && radio_max.configured();
|
return radio_min.configured() && radio_max.configured();
|
||||||
|
Loading…
Reference in New Issue
Block a user