AP_AHRS: example fix travis warning
missing function declaration implicit cast some style fix
This commit is contained in:
parent
320c5e1b96
commit
fede727d38
@ -8,6 +8,9 @@
|
|||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
|
void setup();
|
||||||
|
void loop();
|
||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
// INS and Baro declaration
|
// INS and Baro declaration
|
||||||
@ -34,10 +37,6 @@ static DummyVehicle vehicle;
|
|||||||
// AP_AHRS_DCM ahrs(ins, baro, gps);
|
// AP_AHRS_DCM ahrs(ins, baro, gps);
|
||||||
AP_AHRS_NavEKF ahrs(vehicle.ahrs);
|
AP_AHRS_NavEKF ahrs(vehicle.ahrs);
|
||||||
|
|
||||||
|
|
||||||
#define HIGH 1
|
|
||||||
#define LOW 0
|
|
||||||
|
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
AP_BoardConfig{}.init();
|
AP_BoardConfig{}.init();
|
||||||
@ -68,7 +67,7 @@ void loop(void)
|
|||||||
}
|
}
|
||||||
last_t = now;
|
last_t = now;
|
||||||
|
|
||||||
if (now - last_compass > 100*1000UL &&
|
if (now - last_compass > 100 * 1000UL &&
|
||||||
compass.read()) {
|
compass.read()) {
|
||||||
heading = compass.calculate_heading(ahrs.get_rotation_body_to_ned());
|
heading = compass.calculate_heading(ahrs.get_rotation_body_to_ned());
|
||||||
// read compass at 10Hz
|
// read compass at 10Hz
|
||||||
@ -83,14 +82,14 @@ void loop(void)
|
|||||||
hal.console->printf(
|
hal.console->printf(
|
||||||
"r:%4.1f p:%4.1f y:%4.1f "
|
"r:%4.1f p:%4.1f y:%4.1f "
|
||||||
"drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n",
|
"drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n",
|
||||||
ToDeg(ahrs.roll),
|
(double)ToDeg(ahrs.roll),
|
||||||
ToDeg(ahrs.pitch),
|
(double)ToDeg(ahrs.pitch),
|
||||||
ToDeg(ahrs.yaw),
|
(double)ToDeg(ahrs.yaw),
|
||||||
ToDeg(drift.x),
|
(double)ToDeg(drift.x),
|
||||||
ToDeg(drift.y),
|
(double)ToDeg(drift.y),
|
||||||
ToDeg(drift.z),
|
(double)ToDeg(drift.z),
|
||||||
compass.use_for_yaw() ? ToDeg(heading) : 0.0f,
|
(double)(compass.use_for_yaw() ? ToDeg(heading) : 0.0f),
|
||||||
(1.0e6f*counter)/(now-last_print));
|
(double)((1.0e6f * counter) / (now-last_print)));
|
||||||
last_print = now;
|
last_print = now;
|
||||||
counter = 0;
|
counter = 0;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user