mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Cleaned up AP_GPS formatting.
This commit is contained in:
parent
dd0ac600b3
commit
57301ce647
@ -10,3 +10,4 @@ format ArduRover
|
||||
format ArduBoat
|
||||
format libraries/APO
|
||||
format libraries/AP_Common
|
||||
format libraries/AP_GPS
|
||||
|
@ -41,8 +41,8 @@ AP_GPS_406::_configure_gps(void)
|
||||
const uint8_t gps_checksum[] = {0xA8, 0xAA, 0xAD, 0xAF, 0xC1};
|
||||
const uint8_t gps_ender[] = {0xB0, 0xB3};
|
||||
|
||||
for(int z = 0; z < 2; z++){
|
||||
for(int x = 0; x < 5; x++){
|
||||
for(int z = 0; z < 2; z++) {
|
||||
for(int x = 0; x < 5; x++) {
|
||||
_port->write(gps_header, sizeof(gps_header)); // Prints the msg header, is the same header for all msg..
|
||||
_port->write(gps_payload[x]); // Prints the payload, is not the same for every msg
|
||||
for(int y = 0; y < 6; y++) // Prints 6 zeros
|
||||
|
@ -56,12 +56,12 @@ AP_GPS_IMU::read(void)
|
||||
|
||||
numc = _port->available();
|
||||
|
||||
if (numc > 0){
|
||||
for (int i=0;i<numc;i++){ // Process bytes received
|
||||
if (numc > 0) {
|
||||
for (int i=0; i<numc; i++) { // Process bytes received
|
||||
|
||||
data = _port->read();
|
||||
|
||||
switch(step){ //Normally we start from zero. This is a state machine
|
||||
switch(step) { //Normally we start from zero. This is a state machine
|
||||
case 0:
|
||||
if(data == 0x44) // IMU sync char 1
|
||||
step++; //OH first data packet is correct, so jump to the next step
|
||||
@ -92,7 +92,7 @@ AP_GPS_IMU::read(void)
|
||||
payload_length = data;
|
||||
checksum(payload_length);
|
||||
step++;
|
||||
if (payload_length > 28){
|
||||
if (payload_length > 28) {
|
||||
step = 0; //Bad data, so restart to step zero and try again.
|
||||
payload_counter = 0;
|
||||
ck_a = 0;
|
||||
|
@ -7,7 +7,7 @@
|
||||
#define MAXPAYLOAD 32
|
||||
|
||||
class AP_GPS_IMU : public GPS {
|
||||
public:
|
||||
public:
|
||||
|
||||
// Methods
|
||||
AP_GPS_IMU(Stream *s);
|
||||
@ -25,7 +25,7 @@ class AP_GPS_IMU : public GPS {
|
||||
virtual void setHIL(long time, float latitude, float longitude, float altitude,
|
||||
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
|
||||
|
||||
private:
|
||||
private:
|
||||
// Packet checksums
|
||||
uint8_t ck_a;
|
||||
uint8_t ck_b;
|
||||
|
@ -56,13 +56,13 @@ AP_GPS_MTK::read(void)
|
||||
bool parsed = false;
|
||||
|
||||
numc = _port->available();
|
||||
for (int i = 0; i < numc; i++){ // Process bytes received
|
||||
for (int i = 0; i < numc; i++) { // Process bytes received
|
||||
|
||||
// read the next byte
|
||||
data = _port->read();
|
||||
|
||||
restart:
|
||||
switch(_step){
|
||||
switch(_step) {
|
||||
|
||||
// Message preamble, class, ID detection
|
||||
//
|
||||
|
@ -64,7 +64,7 @@ AP_GPS_MTK16::read(void)
|
||||
data = _port->read();
|
||||
|
||||
restart:
|
||||
switch(_step){
|
||||
switch(_step) {
|
||||
|
||||
// Message preamble, class, ID detection
|
||||
//
|
||||
|
@ -10,6 +10,8 @@ class AP_GPS_None : public GPS
|
||||
public:
|
||||
AP_GPS_None(Stream *s) : GPS(s) {}
|
||||
virtual void init(void) {};
|
||||
virtual bool read(void) { return false; };
|
||||
virtual bool read(void) {
|
||||
return false;
|
||||
};
|
||||
};
|
||||
#endif
|
||||
|
@ -65,7 +65,7 @@ AP_GPS_SIRF::read(void)
|
||||
// read the next byte
|
||||
data = _port->read();
|
||||
|
||||
switch(_step){
|
||||
switch(_step) {
|
||||
|
||||
// Message preamble detection
|
||||
//
|
||||
|
@ -49,12 +49,12 @@ AP_GPS_UBLOX::read(void)
|
||||
bool parsed = false;
|
||||
|
||||
numc = _port->available();
|
||||
for (int i = 0; i < numc; i++){ // Process bytes received
|
||||
for (int i = 0; i < numc; i++) { // Process bytes received
|
||||
|
||||
// read the next byte
|
||||
data = _port->read();
|
||||
|
||||
switch(_step){
|
||||
switch(_step) {
|
||||
|
||||
// Message preamble detection
|
||||
//
|
||||
|
@ -43,7 +43,9 @@ public:
|
||||
///
|
||||
/// @returns Current GPS status
|
||||
///
|
||||
GPS_Status status(void) { return _status; }
|
||||
GPS_Status status(void) {
|
||||
return _status;
|
||||
}
|
||||
|
||||
/// GPS time epoch codes
|
||||
///
|
||||
@ -59,7 +61,9 @@ public:
|
||||
///
|
||||
/// @returns Current GPS time epoch code
|
||||
///
|
||||
GPS_Time_Epoch epoch(void) { return _epoch; }
|
||||
GPS_Time_Epoch epoch(void) {
|
||||
return _epoch;
|
||||
}
|
||||
|
||||
/// Startup initialisation.
|
||||
///
|
||||
|
@ -34,7 +34,7 @@ void loop()
|
||||
{
|
||||
delay(20);
|
||||
gps.update();
|
||||
if (gps.new_data){
|
||||
if (gps.new_data) {
|
||||
Serial.print("gps:");
|
||||
Serial.print(" Lat:");
|
||||
Serial.print((float)gps.latitude / T7, DEC);
|
||||
|
@ -29,7 +29,7 @@ void setup()
|
||||
void loop()
|
||||
{
|
||||
gps->update();
|
||||
if (gps->new_data){
|
||||
if (gps->new_data) {
|
||||
if (gps->fix) {
|
||||
Serial.printf("\nLat: %.7f Lon: %.7f Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu",
|
||||
(float)gps->latitude / T7,
|
||||
|
@ -32,7 +32,7 @@ void loop()
|
||||
{
|
||||
delay(20);
|
||||
gps.update();
|
||||
if (gps.new_data){
|
||||
if (gps.new_data) {
|
||||
Serial.print("gps:");
|
||||
Serial.print(" Lat:");
|
||||
Serial.print((float)gps.latitude / T7, DEC);
|
||||
|
@ -32,7 +32,8 @@ const uint8_t sirf_to_nmea[] = { 0xa0, 0xa2, // preamble
|
||||
0x00, 0x00, // pad
|
||||
0x96, 0x00, // 38400
|
||||
0x01, 0x25, // checksum TBD
|
||||
0xb0, 0xb3 }; // postamble
|
||||
0xb0, 0xb3
|
||||
}; // postamble
|
||||
|
||||
void setup()
|
||||
{
|
||||
@ -52,7 +53,7 @@ void setup()
|
||||
void loop()
|
||||
{
|
||||
gps->update();
|
||||
if (gps->new_data){
|
||||
if (gps->new_data) {
|
||||
if (gps->fix) {
|
||||
Serial.printf("\nLat: %.7f Lon: %.7f Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu",
|
||||
(float)gps->latitude / T7,
|
||||
|
@ -32,7 +32,7 @@ void loop()
|
||||
{
|
||||
delay(20);
|
||||
gps.update();
|
||||
if (gps.new_data){
|
||||
if (gps.new_data) {
|
||||
Serial.print("gps:");
|
||||
Serial.print(" Lat:");
|
||||
Serial.print((float)gps.latitude / T7, DEC);
|
||||
|
Loading…
Reference in New Issue
Block a user