mirror of https://github.com/ArduPilot/ardupilot
AP_Frsky_Telem: Fix some typos
Fixed some typos found in the code.
This commit is contained in:
parent
a56f5d7a45
commit
590db701d0
|
@ -71,8 +71,8 @@ void AP_Frsky_D::send(void)
|
||||||
send_uint16(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360)); // send heading in degree based on AHRS and not GPS
|
send_uint16(DATA_ID_GPS_COURS_BP, (uint16_t)((_ahrs.yaw_sensor / 100) % 360)); // send heading in degree based on AHRS and not GPS
|
||||||
calc_gps_position();
|
calc_gps_position();
|
||||||
if (AP::gps().status() >= 3) {
|
if (AP::gps().status() >= 3) {
|
||||||
send_uint16(DATA_ID_GPS_LAT_BP, _SPort_data.latdddmm); // send gps lattitude degree and minute integer part
|
send_uint16(DATA_ID_GPS_LAT_BP, _SPort_data.latdddmm); // send gps latitude degree and minute integer part
|
||||||
send_uint16(DATA_ID_GPS_LAT_AP, _SPort_data.latmmmm); // send gps lattitude minutes decimal part
|
send_uint16(DATA_ID_GPS_LAT_AP, _SPort_data.latmmmm); // send gps latitude minutes decimal part
|
||||||
send_uint16(DATA_ID_GPS_LAT_NS, _SPort_data.lat_ns); // send gps North / South information
|
send_uint16(DATA_ID_GPS_LAT_NS, _SPort_data.lat_ns); // send gps North / South information
|
||||||
send_uint16(DATA_ID_GPS_LONG_BP, _SPort_data.londddmm); // send gps longitude degree and minute integer part
|
send_uint16(DATA_ID_GPS_LONG_BP, _SPort_data.londddmm); // send gps longitude degree and minute integer part
|
||||||
send_uint16(DATA_ID_GPS_LONG_AP, _SPort_data.lonmmmm); // send gps longitude minutes decimal part
|
send_uint16(DATA_ID_GPS_LONG_AP, _SPort_data.lonmmmm); // send gps longitude minutes decimal part
|
||||||
|
|
|
@ -20,7 +20,7 @@ void AP_Frsky_MAVlite_SPortToMAVlite::update_checksum(const uint8_t c)
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Parses sport packets and if successfull fills the rxmsg mavlite struct
|
Parses sport packets and if successful fills the rxmsg mavlite struct
|
||||||
*/
|
*/
|
||||||
bool AP_Frsky_MAVlite_SPortToMAVlite::process(AP_Frsky_MAVlite_Message &rxmsg, const AP_Frsky_SPort::sport_packet_t &packet)
|
bool AP_Frsky_MAVlite_SPortToMAVlite::process(AP_Frsky_MAVlite_Message &rxmsg, const AP_Frsky_SPort::sport_packet_t &packet)
|
||||||
{
|
{
|
||||||
|
|
Loading…
Reference in New Issue