Browse Source

Sub: set cam mount to 0,0,0 and RC mode after initialization

zr-v5.1
Willian Galvani 5 years ago committed by Jacob Walser
parent
commit
acfe02dbf0
  1. 4
      ArduSub/system.cpp

4
ArduSub/system.cpp

@ -133,6 +133,10 @@ void Sub::init_ardupilot() @@ -133,6 +133,10 @@ void Sub::init_ardupilot()
#if MOUNT == ENABLED
// initialise camera mount
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
#ifdef USERHOOK_INIT

Loading…
Cancel
Save