mirror of https://github.com/ArduPilot/ardupilot
Tracker: remove servo debug
This commit is contained in:
parent
704a720412
commit
a43a8ccfa0
|
@ -147,18 +147,6 @@ static void update_yaw_position_servo(float yaw)
|
|||
int32_t yaw_cd = wrap_180_cd(yaw*100);
|
||||
const int16_t margin = 500; // 5 degrees slop
|
||||
|
||||
static uint16_t count = 0;
|
||||
static uint32_t last_millis= 0;
|
||||
uint32_t millis = hal.scheduler->millis();
|
||||
if (millis > last_millis + 1000)
|
||||
{
|
||||
// hal.uartA->printf("ahrs_yaw_cd %ld yaw_cd %ld\n", ahrs_yaw_cd, yaw_cd);
|
||||
// hal.uartA->printf("count %d\n", count);
|
||||
last_millis = millis;
|
||||
count = 0;
|
||||
}
|
||||
count++;
|
||||
|
||||
// Antenna as Ballerina. Use with antenna that do not have continuously rotating servos, ie at some point in rotation
|
||||
// the servo limits are reached and the servo has to slew 360 degrees to the 'other side' to keep tracking.
|
||||
//
|
||||
|
|
Loading…
Reference in New Issue