mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_Compass: example fix travis warning
missing function declaration implicit cast some style fix
This commit is contained in:
parent
2200302081
commit
d3e27d8720
@ -45,7 +45,7 @@ static void loop()
|
|||||||
if ((AP_HAL::micros() - timer) > 100000L) {
|
if ((AP_HAL::micros() - timer) > 100000L) {
|
||||||
timer = AP_HAL::micros();
|
timer = AP_HAL::micros();
|
||||||
compass.read();
|
compass.read();
|
||||||
unsigned long read_time = AP_HAL::micros() - timer;
|
const uint32_t read_time = AP_HAL::micros() - timer;
|
||||||
|
|
||||||
for (uint8_t i = 0; i < compass_count; i++) {
|
for (uint8_t i = 0; i < compass_count; i++) {
|
||||||
float heading;
|
float heading;
|
||||||
@ -81,15 +81,17 @@ static void loop()
|
|||||||
offset[i][2] = -(max[i][2] + min[i][2]) / 2;
|
offset[i][2] = -(max[i][2] + min[i][2]) / 2;
|
||||||
|
|
||||||
// display all to user
|
// display all to user
|
||||||
hal.console->printf("Heading: %.2f (%3d,%3d,%3d)",
|
hal.console->printf("Heading: %.2f (%3d, %3d, %3d)",
|
||||||
ToDeg(heading),
|
(double)ToDeg(heading),
|
||||||
(int)mag.x,
|
(int)mag.x,
|
||||||
(int)mag.y,
|
(int)mag.y,
|
||||||
(int)mag.z);
|
(int)mag.z);
|
||||||
|
|
||||||
// display offsets
|
// display offsets
|
||||||
hal.console->printf(" offsets(%.2f, %.2f, %.2f)",
|
hal.console->printf(" offsets(%.2f, %.2f, %.2f)",
|
||||||
offset[i][0], offset[i][1], offset[i][2]);
|
(double)offset[i][0],
|
||||||
|
(double)offset[i][1],
|
||||||
|
(double)offset[i][2]);
|
||||||
|
|
||||||
hal.console->printf(" t=%u", (unsigned)read_time);
|
hal.console->printf(" t=%u", (unsigned)read_time);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user