mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tracker: use floats for get/set output scaled
This commit is contained in:
parent
73b0a212f7
commit
8b34f2f48c
@ -74,7 +74,7 @@ void Tracker::update_pitch_position_servo()
|
|||||||
// PITCH2SRV_IMAX 4000.000000
|
// PITCH2SRV_IMAX 4000.000000
|
||||||
|
|
||||||
// calculate new servo position
|
// calculate new servo position
|
||||||
int32_t new_servo_out = SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_pitch) + g.pidPitch2Srv.update_error(nav_status.angle_error_pitch);
|
float new_servo_out = SRV_Channels::get_output_scaled(SRV_Channel::k_tracker_pitch) + g.pidPitch2Srv.update_error(nav_status.angle_error_pitch);
|
||||||
|
|
||||||
// position limit pitch servo
|
// position limit pitch servo
|
||||||
if (new_servo_out <= pitch_min_cd) {
|
if (new_servo_out <= pitch_min_cd) {
|
||||||
|
Loading…
Reference in New Issue
Block a user