Subversion Repositories NaviCtrl

Rev

Rev 720 | Rev 739 | Go to most recent revision | Show entire file | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 720 Rev 735
Line 651... Line 651...
651
                           case 7:
651
                           case 7:
652
                                // Target Bearing in deg
652
                                // Target Bearing in deg
653
                                sprintf(string, "<TargetBearing>%03d</TargetBearing>\r\n", NaviData.TargetPositionDeviation.Bearing);
653
                                sprintf(string, "<TargetBearing>%03d</TargetBearing>\r\n", NaviData.TargetPositionDeviation.Bearing);
654
                                CheckSumAndWrite(&Check16Block,string, doc->file);
654
                                CheckSumAndWrite(&Check16Block,string, doc->file);
655
                                // Target Distance in dm
655
                                // Target Distance in dm
656
                                sprintf(string, "<TargetDistance>%d</TargetDistance>\r\n", NaviData.TargetPositionDeviation.Distance);
656
                                sprintf(string, "<TargetDistance>%d</TargetDistance>\r\n", NaviData.TargetPositionDeviation.Distance_dm);
657
                                CheckSumAndWrite(&Check16Block,string, doc->file);
657
                                CheckSumAndWrite(&Check16Block,string, doc->file);
658
                                // Course in deg
658
                                // Course in deg
659
                                sprintf(string, "<Course>%03d</Course>\r\n", NaviData.Heading);
659
                                sprintf(string, "<Course>%03d</Course>\r\n", NaviData.Heading);
660
                                CheckSumAndWrite(&Check16Block,string, doc->file);
660
                                CheckSumAndWrite(&Check16Block,string, doc->file);
661
                                // Ground Speed in cm/s
661
                                // Ground Speed in cm/s