mirror of https://github.com/ArduPilot/ardupilot
Copter: stop providing current location to mount
This commit is contained in:
parent
c39a344414
commit
38d3c2daa1
|
@ -496,8 +496,7 @@ private:
|
||||||
|
|
||||||
// Camera/Antenna mount tracking and stabilisation stuff
|
// Camera/Antenna mount tracking and stabilisation stuff
|
||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
// current_loc uses the baro/gps solution for altitude rather than gps only.
|
AP_Mount camera_mount;
|
||||||
AP_Mount camera_mount{current_loc};
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// AC_Fence library to reduce fly-aways
|
// AC_Fence library to reduce fly-aways
|
||||||
|
|
Loading…
Reference in New Issue