Browse Source

Tracker: compile warnings: float to double. print statements require doubles

mission-4.1.18
Tom Pittenger 10 years ago committed by Andrew Tridgell
parent
commit
0e3d54d9e4
  1. 2
      AntennaTracker/servos.pde

2
AntennaTracker/servos.pde

@ -52,7 +52,7 @@ static void update_pitch_position_servo(float pitch)
// pitch argument is -90 to 90, where 0 is horizontal // pitch argument is -90 to 90, where 0 is horizontal
// servo_out is in 100ths of a degree // servo_out is in 100ths of a degree
float ahrs_pitch = ahrs.pitch_sensor*0.01f; float ahrs_pitch = ahrs.pitch_sensor*0.01f;
int32_t angle_err = -(ahrs_pitch - pitch) * 100.0; int32_t angle_err = -(ahrs_pitch - pitch) * 100.0f;
int32_t pitch_limit_cd = g.pitch_range*100/2; int32_t pitch_limit_cd = g.pitch_range*100/2;
// Need to configure your servo so that increasing servo_out causes increase in pitch/elevation (ie pointing higher into the sky, // Need to configure your servo so that increasing servo_out causes increase in pitch/elevation (ie pointing higher into the sky,
// above the horizon. On my antenna tracker this requires the pitch/elevation servo to be reversed // above the horizon. On my antenna tracker this requires the pitch/elevation servo to be reversed

Loading…
Cancel
Save