mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
mavlink: CAMERA_TRIGGER stream check free tx buf before send
This commit is contained in:
committed by
Lorenz Meier
parent
ae706537b8
commit
ceadcd74d0
@@ -2131,7 +2131,12 @@ public:
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return _trigger_sub.advertised() ? MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
|
||||
if (_trigger_sub.advertised()) {
|
||||
return MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES
|
||||
+ MAVLINK_MSG_ID_COMMAND_LONG_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; // TODO: MAV_CMD_DO_DIGICAM_CONTROL
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
private:
|
||||
@@ -2149,7 +2154,7 @@ protected:
|
||||
{
|
||||
camera_trigger_s trigger;
|
||||
|
||||
if (_trigger_sub.update(&trigger)) {
|
||||
if ((_mavlink->get_free_tx_buf() >= get_size()) && _trigger_sub.update(&trigger)) {
|
||||
mavlink_camera_trigger_t msg{};
|
||||
|
||||
msg.time_usec = trigger.timestamp;
|
||||
|
||||
Reference in New Issue
Block a user