mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Commented out debugging in guide.
This commit is contained in:
parent
48ad2d1ed1
commit
ed26538c45
@ -194,9 +194,9 @@ void MavlinkGuide::handleCommand() {
|
||||
float bearing = _previousCommand.bearingTo(_command);
|
||||
_headingCommand = bearing - temp;
|
||||
_yawCommand = _command.getYawCommand();
|
||||
_hal->debug->printf_P(
|
||||
PSTR("nav: bCurrent2Dest: %f\tdXt: %f\tcmdHeading: %f\tnextWpDistance: %f\talongTrack: %f\tyaw command: %f\n"),
|
||||
bearing * rad2Deg, dXt, _headingCommand * rad2Deg, getDistanceToNextWaypoint(), alongTrack, _yawCommand*rad2Deg);
|
||||
//_hal->debug->printf_P(
|
||||
//PSTR("nav: bCurrent2Dest: %f\tdXt: %f\tcmdHeading: %f\tnextWpDistance: %f\talongTrack: %f\tyaw command: %f\n"),
|
||||
//bearing * rad2Deg, dXt, _headingCommand * rad2Deg, getDistanceToNextWaypoint(), alongTrack, _yawCommand*rad2Deg);
|
||||
|
||||
// for these modes just head to current command
|
||||
} else if (
|
||||
|
Loading…
Reference in New Issue
Block a user