Copter: make optflow available to AHRS
This commit is contained in:
parent
8f571f1225
commit
788bb8ab9f
@ -216,6 +216,9 @@ static void init_ardupilot()
|
|||||||
if(g.compass_enabled)
|
if(g.compass_enabled)
|
||||||
init_compass();
|
init_compass();
|
||||||
|
|
||||||
|
// make optflow available to AHRS
|
||||||
|
ahrs.set_optflow(&optflow);
|
||||||
|
|
||||||
// initialise attitude and position controllers
|
// initialise attitude and position controllers
|
||||||
attitude_control.set_dt(MAIN_LOOP_SECONDS);
|
attitude_control.set_dt(MAIN_LOOP_SECONDS);
|
||||||
pos_control.set_dt(MAIN_LOOP_SECONDS);
|
pos_control.set_dt(MAIN_LOOP_SECONDS);
|
||||||
|
@ -96,6 +96,7 @@ test_compass(uint8_t argc, const Menu::arg *argv)
|
|||||||
ahrs.init();
|
ahrs.init();
|
||||||
ahrs.set_fly_forward(true);
|
ahrs.set_fly_forward(true);
|
||||||
ahrs.set_compass(&compass);
|
ahrs.set_compass(&compass);
|
||||||
|
ahrs.set_optflow(&optflow);
|
||||||
report_compass();
|
report_compass();
|
||||||
|
|
||||||
// we need the AHRS initialised for this test
|
// we need the AHRS initialised for this test
|
||||||
|
Loading…
Reference in New Issue
Block a user