mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
RC_Channel: added pwm_to_angle_dz() function
will be used by k_aileron in APM
This commit is contained in:
parent
df96832900
commit
3a1f85a4b0
@ -217,13 +217,15 @@ RC_Channel::update_min_max()
|
|||||||
radio_max = max(radio_max.get(), radio_in);
|
radio_max = max(radio_max.get(), radio_in);
|
||||||
}
|
}
|
||||||
|
|
||||||
// ------------------------------------------
|
/*
|
||||||
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
||||||
|
the current radio_in value using the specified dead_zone
|
||||||
|
*/
|
||||||
int16_t
|
int16_t
|
||||||
RC_Channel::pwm_to_angle()
|
RC_Channel::pwm_to_angle_dz(int16_t dead_zone)
|
||||||
{
|
{
|
||||||
int16_t radio_trim_high = radio_trim + _dead_zone;
|
int16_t radio_trim_high = radio_trim + dead_zone;
|
||||||
int16_t radio_trim_low = radio_trim - _dead_zone;
|
int16_t radio_trim_low = radio_trim - dead_zone;
|
||||||
|
|
||||||
// prevent div by 0
|
// prevent div by 0
|
||||||
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
||||||
@ -237,6 +239,16 @@ RC_Channel::pwm_to_angle()
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
||||||
|
the current radio_in value
|
||||||
|
*/
|
||||||
|
int16_t
|
||||||
|
RC_Channel::pwm_to_angle()
|
||||||
|
{
|
||||||
|
return pwm_to_angle_dz(_dead_zone);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
int16_t
|
int16_t
|
||||||
RC_Channel::angle_to_pwm()
|
RC_Channel::angle_to_pwm()
|
||||||
|
@ -78,6 +78,7 @@ public:
|
|||||||
// includes offset from PWM
|
// includes offset from PWM
|
||||||
//int16_t get_radio_out(void);
|
//int16_t get_radio_out(void);
|
||||||
|
|
||||||
|
int16_t pwm_to_angle_dz(int16_t dead_zone);
|
||||||
int16_t pwm_to_angle();
|
int16_t pwm_to_angle();
|
||||||
float norm_input();
|
float norm_input();
|
||||||
float norm_output();
|
float norm_output();
|
||||||
|
Loading…
Reference in New Issue
Block a user