AP_Mount: fix SToRM32 Serial protocol delay

The packets to a SToRM32 gimbal were being sent at 1s intervals when in MAVLINK targeting mode.
We need to send them faster or smooth targetting is impossible.
This commit is contained in:
HITMAnsOFT 2018-12-20 13:01:48 +04:00 committed by Francisco Ferreira
parent 70c1414026
commit 9c26b5bb9c
2 changed files with 2 additions and 0 deletions

View File

@ -46,6 +46,7 @@ void AP_Mount_SToRM32::update()
// point to the angles given by a mavlink message
case MAV_MOUNT_MODE_MAVLINK_TARGETING:
// do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
resend_now = true;
break;
// RC radio manual angle control, but with stabilization from the AHRS

View File

@ -60,6 +60,7 @@ void AP_Mount_SToRM32_serial::update()
// point to the angles given by a mavlink message
case MAV_MOUNT_MODE_MAVLINK_TARGETING:
// do nothing because earth-frame angle targets (i.e. _angle_ef_target_rad) should have already been set by a MOUNT_CONTROL message from GCS
resend_now = true;
break;
// RC radio manual angle control, but with stabilization from the AHRS