mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
change rc norm_output to scale evenly across the entire range
This commit is contained in:
parent
9ca6668c1b
commit
6b949511ca
@ -420,7 +420,7 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
|||||||
(float)airspeed / 100.0,
|
(float)airspeed / 100.0,
|
||||||
(float)g_gps->ground_speed / 100.0,
|
(float)g_gps->ground_speed / 100.0,
|
||||||
(dcm.yaw_sensor / 100) % 360,
|
(dcm.yaw_sensor / 100) % 360,
|
||||||
(uint16_t)(100 * g.channel_throttle.norm_output()),
|
(uint16_t)(100 * (g.channel_throttle.norm_output() / 2.0 + 0.5)), // scale -1,1 to 0-100
|
||||||
current_loc.alt / 100.0,
|
current_loc.alt / 100.0,
|
||||||
0);
|
0);
|
||||||
}
|
}
|
||||||
|
@ -248,10 +248,12 @@ RC_Channel::norm_input()
|
|||||||
float
|
float
|
||||||
RC_Channel::norm_output()
|
RC_Channel::norm_output()
|
||||||
{
|
{
|
||||||
|
uint16_t mid = (radio_max + radio_min) / 2;
|
||||||
|
|
||||||
if(radio_out < radio_trim)
|
if(radio_out < radio_trim)
|
||||||
return (float)(radio_out - radio_trim) / (float)(radio_trim - radio_min);
|
return (float)(radio_out - mid) / (float)(mid - radio_min);
|
||||||
else
|
else
|
||||||
return (float)(radio_out - radio_trim) / (float)(radio_max - radio_trim);
|
return (float)(radio_out - mid) / (float)(radio_max - mid);
|
||||||
}
|
}
|
||||||
|
|
||||||
void RC_Channel::set_apm_rc( APM_RC_Class * apm_rc )
|
void RC_Channel::set_apm_rc( APM_RC_Class * apm_rc )
|
||||||
|
Loading…
Reference in New Issue
Block a user