AP_Mount: Siyi loses unused center method

This commit is contained in:
Randy Mackay 2023-06-21 09:09:48 +09:00
parent 98310d861e
commit 5d97a4b3d6
2 changed files with 0 additions and 9 deletions

View File

@ -559,12 +559,6 @@ void AP_Mount_Siyi::rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool y
send_packet(SiyiCommandId::GIMBAL_ROTATION, yaw_and_pitch_rates, ARRAY_SIZE(yaw_and_pitch_rates));
}
// center gimbal
void AP_Mount_Siyi::center_gimbal()
{
send_1byte_packet(SiyiCommandId::CENTER, 1);
}
// set gimbal's lock vs follow mode
// lock should be true if gimbal should maintain an earth-frame target
// lock is false to follow / maintain a body-frame target

View File

@ -172,9 +172,6 @@ private:
// yaw_is_ef should be true if gimbal should maintain an earth-frame target (aka lock)
void rotate_gimbal(int8_t pitch_scalar, int8_t yaw_scalar, bool yaw_is_ef);
// center gimbal
void center_gimbal();
// set gimbal's lock vs follow mode
// lock should be true if gimbal should maintain an earth-frame target
// lock is false to follow / maintain a body-frame target