mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 17:34:01 -04:00
Sub: set cam mount to 0,0,0 and RC mode after initialization
This commit is contained in:
parent
a8f250c99a
commit
ee2bea5256
@ -129,6 +129,10 @@ void Sub::init_ardupilot()
|
|||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
// initialise camera mount
|
// initialise camera mount
|
||||||
camera_mount.init();
|
camera_mount.init();
|
||||||
|
// This step ncessary so the servo is properly initialized
|
||||||
|
camera_mount.set_angle_targets(0, 0, 0);
|
||||||
|
// for some reason the call to set_angle_targets changes the mode to mavlink targeting!
|
||||||
|
camera_mount.set_mode(MAV_MOUNT_MODE_RC_TARGETING);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USERHOOK_INIT
|
#ifdef USERHOOK_INIT
|
||||||
|
Loading…
Reference in New Issue
Block a user