mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
RC_Channel: rename within_min_dz to in_min_dz for consistency
... consistency with in_trim_dz
This commit is contained in:
parent
515db96858
commit
30c08c1e7c
@ -332,7 +332,7 @@ bool RC_Channel::in_trim_dz() const
|
||||
/*
|
||||
return trues if input is within deadzone of min
|
||||
*/
|
||||
bool RC_Channel::within_min_dz() const
|
||||
bool RC_Channel::in_min_dz() const
|
||||
{
|
||||
return radio_in < radio_min + dead_zone;
|
||||
}
|
||||
|
@ -53,7 +53,7 @@ public:
|
||||
float norm_input_ignore_trim() const;
|
||||
|
||||
// returns true if input is within deadzone of min
|
||||
bool within_min_dz() const;
|
||||
bool in_min_dz() const;
|
||||
|
||||
uint8_t percent_input() const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user