mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: ignore rc trim when calculating desired mount angles
This commit is contained in:
parent
52520d9c28
commit
9fe8e01fe4
@ -128,7 +128,7 @@ void AP_Mount_Backend::update_targets_from_rc()
|
|||||||
// returns the angle (radians) that the RC_Channel input is receiving
|
// returns the angle (radians) that the RC_Channel input is receiving
|
||||||
float AP_Mount_Backend::angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max)
|
float AP_Mount_Backend::angle_input_rad(const RC_Channel* rc, int16_t angle_min, int16_t angle_max)
|
||||||
{
|
{
|
||||||
return radians(((rc->norm_input() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f);
|
return radians(((rc->norm_input_ignore_trim() + 1.0f) * 0.5f * (angle_max - angle_min) + angle_min)*0.01f);
|
||||||
}
|
}
|
||||||
|
|
||||||
// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target
|
// calc_angle_to_location - calculates the earth-frame roll, tilt and pan angles (and radians) to point at the given target
|
||||||
|
Loading…
Reference in New Issue
Block a user