mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
uncrustify libraries/AP_GPS/AP_GPS_IMU.cpp
This commit is contained in:
parent
5ed90851e3
commit
89bd01f86e
@ -1,37 +1,37 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
||||||
/*
|
/*
|
||||||
GPS_MTK.cpp - Ublox GPS library for Arduino
|
* GPS_MTK.cpp - Ublox GPS library for Arduino
|
||||||
Code by Jordi Mu<EFBFBD>oz and Jose Julio. DIYDrones.com
|
* Code by Jordi Mu<EFBFBD>oz and Jose Julio. DIYDrones.com
|
||||||
This code works with boards based on ATMega168/328 and ATMega1280 (Serial port 1)
|
* This code works with boards based on ATMega168/328 and ATMega1280 (Serial port 1)
|
||||||
|
*
|
||||||
This library is free software; you can redistribute it and/or
|
* This library is free software; you can redistribute it and/or
|
||||||
modify it under the terms of the GNU Lesser General Public
|
* modify it under the terms of the GNU Lesser General Public
|
||||||
License as published by the Free Software Foundation; either
|
* License as published by the Free Software Foundation; either
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
* version 2.1 of the License, or (at your option) any later version.
|
||||||
|
*
|
||||||
GPS configuration : Costum protocol
|
* GPS configuration : Costum protocol
|
||||||
Baud rate : 38400
|
* Baud rate : 38400
|
||||||
|
*
|
||||||
Methods:
|
* Methods:
|
||||||
init() : GPS initialization
|
* init() : GPS initialization
|
||||||
update() : Call this funcion as often as you want to ensure you read the incomming gps data
|
* update() : Call this funcion as often as you want to ensure you read the incomming gps data
|
||||||
|
*
|
||||||
Properties:
|
* Properties:
|
||||||
lattitude : lattitude * 10000000 (int32_t value)
|
* lattitude : lattitude * 10000000 (int32_t value)
|
||||||
longitude : longitude * 10000000 (int32_t value)
|
* longitude : longitude * 10000000 (int32_t value)
|
||||||
altitude : altitude * 100 (meters) (int32_t value)
|
* altitude : altitude * 100 (meters) (int32_t value)
|
||||||
ground_speed : Speed (m/s) * 100 (int32_t value)
|
* ground_speed : Speed (m/s) * 100 (int32_t value)
|
||||||
ground_course : Course (degrees) * 100 (int32_t value)
|
* ground_course : Course (degrees) * 100 (int32_t value)
|
||||||
new_data : 1 when a new data is received.
|
* new_data : 1 when a new data is received.
|
||||||
You need to write a 0 to new_data when you read the data
|
* You need to write a 0 to new_data when you read the data
|
||||||
fix : 1: GPS NO fix, 2: 2D fix, 3: 3D fix.
|
* fix : 1: GPS NO fix, 2: 2D fix, 3: 3D fix.
|
||||||
|
*
|
||||||
*/
|
*/
|
||||||
#include "AP_GPS_IMU.h"
|
#include "AP_GPS_IMU.h"
|
||||||
#if defined(ARDUINO) && ARDUINO >= 100
|
#if defined(ARDUINO) && ARDUINO >= 100
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
#else
|
#else
|
||||||
#include "WProgram.h"
|
#include "WProgram.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
@ -154,14 +154,14 @@ AP_GPS_IMU::read(void)
|
|||||||
ck_b = 0;
|
ck_b = 0;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}// End for...
|
} // End for...
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
/****************************************************************
|
/****************************************************************
|
||||||
*
|
*
|
||||||
****************************************************************/
|
****************************************************************/
|
||||||
|
|
||||||
void AP_GPS_IMU::join_data(void)
|
void AP_GPS_IMU::join_data(void)
|
||||||
{
|
{
|
||||||
@ -221,10 +221,10 @@ void AP_GPS_IMU::GPS_join_data(void)
|
|||||||
|
|
||||||
|
|
||||||
/****************************************************************
|
/****************************************************************
|
||||||
*
|
*
|
||||||
****************************************************************/
|
****************************************************************/
|
||||||
// checksum algorithm
|
// checksum algorithm
|
||||||
void AP_GPS_IMU::checksum(unsigned char data)
|
void AP_GPS_IMU::checksum(unsigned char data)
|
||||||
{
|
{
|
||||||
ck_a += data;
|
ck_a += data;
|
||||||
ck_b += ck_a;
|
ck_b += ck_a;
|
||||||
@ -232,7 +232,8 @@ void AP_GPS_IMU::checksum(unsigned char data)
|
|||||||
|
|
||||||
|
|
||||||
/****************************************************************
|
/****************************************************************
|
||||||
* Unused
|
* Unused
|
||||||
****************************************************************/
|
****************************************************************/
|
||||||
void AP_GPS_IMU::setHIL(uint32_t _time, float _latitude, float _longitude, float _altitude,
|
void AP_GPS_IMU::setHIL(uint32_t _time, float _latitude, float _longitude, float _altitude,
|
||||||
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats) {};
|
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats) {
|
||||||
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user