mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_Compass: add more comments to example
This commit is contained in:
parent
1af6178be8
commit
4c809888de
@ -1,3 +1,18 @@
|
|||||||
|
/*
|
||||||
|
This program is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
|
(at your option) any later version.
|
||||||
|
|
||||||
|
This program is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Example of APM_Compass library (HMC5843 sensor).
|
* Example of APM_Compass library (HMC5843 sensor).
|
||||||
* Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
|
* Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
|
||||||
@ -10,10 +25,13 @@
|
|||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
static AP_BoardConfig board_config;
|
static AP_BoardConfig board_config;
|
||||||
|
|
||||||
|
// create compass object
|
||||||
static Compass compass;
|
static Compass compass;
|
||||||
|
|
||||||
uint32_t timer;
|
uint32_t timer;
|
||||||
|
|
||||||
|
// to be called only once on boot for initializing objects
|
||||||
static void setup()
|
static void setup()
|
||||||
{
|
{
|
||||||
hal.console->printf("Compass library test\n");
|
hal.console->printf("Compass library test\n");
|
||||||
@ -32,6 +50,7 @@ static void setup()
|
|||||||
timer = AP_HAL::micros();
|
timer = AP_HAL::micros();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// loop
|
||||||
static void loop()
|
static void loop()
|
||||||
{
|
{
|
||||||
static const uint8_t compass_count = compass.get_count();
|
static const uint8_t compass_count = compass.get_count();
|
||||||
@ -39,6 +58,7 @@ static void loop()
|
|||||||
static float max[COMPASS_MAX_INSTANCES][3];
|
static float max[COMPASS_MAX_INSTANCES][3];
|
||||||
static float offset[COMPASS_MAX_INSTANCES][3];
|
static float offset[COMPASS_MAX_INSTANCES][3];
|
||||||
|
|
||||||
|
// run read() at 10Hz
|
||||||
if ((AP_HAL::micros() - timer) > 100000L) {
|
if ((AP_HAL::micros() - timer) > 100000L) {
|
||||||
timer = AP_HAL::micros();
|
timer = AP_HAL::micros();
|
||||||
compass.read();
|
compass.read();
|
||||||
@ -94,6 +114,8 @@ static void loop()
|
|||||||
hal.console->printf("\n");
|
hal.console->printf("\n");
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
|
// if stipulated time has not passed between two distinct readings, delay the program for a millisecond
|
||||||
hal.scheduler->delay(1);
|
hal.scheduler->delay(1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user