AP_Mount: Backend sends gimbal_device_id in device_attitude_status_send
This commit is contained in:
parent
073e93dfec
commit
55aa1b5a32
@ -139,7 +139,10 @@ void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan
|
||||
std::numeric_limits<double>::quiet_NaN(), // roll axis angular velocity (NaN for unknown)
|
||||
std::numeric_limits<double>::quiet_NaN(), // pitch axis angular velocity (NaN for unknown)
|
||||
std::numeric_limits<double>::quiet_NaN(), // yaw axis angular velocity (NaN for unknown)
|
||||
0); // failure flags (not supported)
|
||||
0, // failure flags (not supported)
|
||||
std::numeric_limits<double>::quiet_NaN(), // delta_yaw (NaN for unknonw)
|
||||
std::numeric_limits<double>::quiet_NaN(), // delta_yaw_velocity (NaN for unknonw)
|
||||
_instance + 1); // gimbal_device_id
|
||||
}
|
||||
|
||||
// return gimbal manager capability flags used by GIMBAL_MANAGER_INFORMATION message
|
||||
|
Loading…
Reference in New Issue
Block a user