AP_Mount: gremsy driver sends vehicle att at 50hz
This commit is contained in:
parent
18fa90e765
commit
df9a2a3485
@ -6,7 +6,7 @@ extern const AP_HAL::HAL& hal;
|
||||
|
||||
#define AP_MOUNT_GREMSY_RESEND_MS 1000 // resend angle targets to gimbal at least once per second
|
||||
#define AP_MOUNT_GREMSY_SEARCH_MS 60000 // search for gimbal for 1 minute after startup
|
||||
#define AP_MOUNT_GREMSY_ATTITUDE_INTERVAL_US 10000 // send ATTITUDE and AUTOPILOT_STATE_FOR_GIMBAL_DEVICE at 100hz
|
||||
#define AP_MOUNT_GREMSY_ATTITUDE_INTERVAL_US 20000 // send ATTITUDE and AUTOPILOT_STATE_FOR_GIMBAL_DEVICE at 50hz
|
||||
|
||||
AP_Mount_Gremsy::AP_Mount_Gremsy(AP_Mount &frontend, AP_Mount_Params ¶ms, uint8_t instance) :
|
||||
AP_Mount_Backend(frontend, params, instance)
|
||||
|
Loading…
Reference in New Issue
Block a user