mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_GPS/AP_GPS_MTK.cpp
This commit is contained in:
parent
cf69da594f
commit
7fa1a9d3b6
|
@ -31,11 +31,11 @@ AP_GPS_MTK::init(enum GPS_Engine_Setting nav_setting)
|
||||||
// set 5Hz update rate
|
// set 5Hz update rate
|
||||||
_port->print(MTK_OUTPUT_5HZ);
|
_port->print(MTK_OUTPUT_5HZ);
|
||||||
|
|
||||||
// set SBAS on
|
// set SBAS on
|
||||||
_port->print(SBAS_ON);
|
_port->print(SBAS_ON);
|
||||||
|
|
||||||
// set WAAS on
|
// set WAAS on
|
||||||
_port->print(WAAS_ON);
|
_port->print(WAAS_ON);
|
||||||
|
|
||||||
// set initial epoch code
|
// set initial epoch code
|
||||||
_epoch = TIME_OF_DAY;
|
_epoch = TIME_OF_DAY;
|
||||||
|
@ -57,12 +57,12 @@ AP_GPS_MTK::init(enum GPS_Engine_Setting nav_setting)
|
||||||
bool
|
bool
|
||||||
AP_GPS_MTK::read(void)
|
AP_GPS_MTK::read(void)
|
||||||
{
|
{
|
||||||
uint8_t data;
|
uint8_t data;
|
||||||
int16_t numc;
|
int16_t numc;
|
||||||
bool parsed = false;
|
bool parsed = false;
|
||||||
|
|
||||||
numc = _port->available();
|
numc = _port->available();
|
||||||
for (int16_t i = 0; i < numc; i++) { // Process bytes received
|
for (int16_t i = 0; i < numc; i++) { // Process bytes received
|
||||||
|
|
||||||
// read the next byte
|
// read the next byte
|
||||||
data = _port->read();
|
data = _port->read();
|
||||||
|
@ -70,15 +70,15 @@ AP_GPS_MTK::read(void)
|
||||||
restart:
|
restart:
|
||||||
switch(_step) {
|
switch(_step) {
|
||||||
|
|
||||||
// Message preamble, class, ID detection
|
// Message preamble, class, ID detection
|
||||||
//
|
//
|
||||||
// If we fail to match any of the expected bytes, we
|
// If we fail to match any of the expected bytes, we
|
||||||
// reset the state machine and re-consider the failed
|
// reset the state machine and re-consider the failed
|
||||||
// byte as the first byte of the preamble. This
|
// byte as the first byte of the preamble. This
|
||||||
// improves our chances of recovering from a mismatch
|
// improves our chances of recovering from a mismatch
|
||||||
// and makes it less likely that we will be fooled by
|
// and makes it less likely that we will be fooled by
|
||||||
// the preamble appearing as data in some other message.
|
// the preamble appearing as data in some other message.
|
||||||
//
|
//
|
||||||
case 0:
|
case 0:
|
||||||
if(PREAMBLE1 == data)
|
if(PREAMBLE1 == data)
|
||||||
_step++;
|
_step++;
|
||||||
|
@ -93,9 +93,9 @@ restart:
|
||||||
case 2:
|
case 2:
|
||||||
if (MESSAGE_CLASS == data) {
|
if (MESSAGE_CLASS == data) {
|
||||||
_step++;
|
_step++;
|
||||||
_ck_b = _ck_a = data; // reset the checksum accumulators
|
_ck_b = _ck_a = data; // reset the checksum accumulators
|
||||||
} else {
|
} else {
|
||||||
_step = 0; // reset and wait for a message of the right class
|
_step = 0; // reset and wait for a message of the right class
|
||||||
goto restart;
|
goto restart;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -110,8 +110,8 @@ restart:
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// Receive message data
|
// Receive message data
|
||||||
//
|
//
|
||||||
case 4:
|
case 4:
|
||||||
_buffer.bytes[_payload_counter++] = data;
|
_buffer.bytes[_payload_counter++] = data;
|
||||||
_ck_b += (_ck_a += data);
|
_ck_b += (_ck_a += data);
|
||||||
|
@ -119,8 +119,8 @@ restart:
|
||||||
_step++;
|
_step++;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
// Checksum and message processing
|
// Checksum and message processing
|
||||||
//
|
//
|
||||||
case 5:
|
case 5:
|
||||||
_step++;
|
_step++;
|
||||||
if (_ck_a != data) {
|
if (_ck_a != data) {
|
||||||
|
@ -135,17 +135,17 @@ restart:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
fix = ((_buffer.msg.fix_type == FIX_3D) ||
|
fix = ((_buffer.msg.fix_type == FIX_3D) ||
|
||||||
(_buffer.msg.fix_type == FIX_3D_SBAS));
|
(_buffer.msg.fix_type == FIX_3D_SBAS));
|
||||||
latitude = _swapl(&_buffer.msg.latitude) * 10;
|
latitude = _swapl(&_buffer.msg.latitude) * 10;
|
||||||
longitude = _swapl(&_buffer.msg.longitude) * 10;
|
longitude = _swapl(&_buffer.msg.longitude) * 10;
|
||||||
altitude = _swapl(&_buffer.msg.altitude);
|
altitude = _swapl(&_buffer.msg.altitude);
|
||||||
ground_speed = _swapl(&_buffer.msg.ground_speed);
|
ground_speed = _swapl(&_buffer.msg.ground_speed);
|
||||||
ground_course = _swapl(&_buffer.msg.ground_course) / 10000;
|
ground_course = _swapl(&_buffer.msg.ground_course) / 10000;
|
||||||
num_sats = _buffer.msg.satellites;
|
num_sats = _buffer.msg.satellites;
|
||||||
|
|
||||||
// time from gps is UTC, but convert here to msToD
|
// time from gps is UTC, but convert here to msToD
|
||||||
int32_t time_utc = _swapl(&_buffer.msg.utc_time);
|
int32_t time_utc = _swapl(&_buffer.msg.utc_time);
|
||||||
int32_t temp = (time_utc/10000000);
|
int32_t temp = (time_utc/10000000);
|
||||||
time_utc -= temp*10000000;
|
time_utc -= temp*10000000;
|
||||||
time = temp * 3600000;
|
time = temp * 3600000;
|
||||||
|
|
Loading…
Reference in New Issue