mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-20 11:23:06 +08:00
mavlink: avoid double trigger using sequence
By adding the sequence number we can avoid double triggering due to command retransmissions. This is according to the mavlink spec for MAV_CMD_IMAGE_START_CAPTURE.
This commit is contained in:
@@ -70,6 +70,7 @@ private:
|
||||
0, //target_sys_id
|
||||
MAV_COMP_ID_CAMERA // active_comp_id
|
||||
};
|
||||
int _sequence {1};
|
||||
|
||||
bool send() override
|
||||
{
|
||||
@@ -90,7 +91,7 @@ private:
|
||||
vcmd.param1 = 0.0f; // all cameras
|
||||
vcmd.param2 = 0.0f; // duration 0 because only taking one picture
|
||||
vcmd.param3 = 1.0f; // only take one
|
||||
vcmd.param4 = NAN;
|
||||
vcmd.param4 = (float)_sequence++;
|
||||
vcmd.param5 = (double)NAN;
|
||||
vcmd.param6 = (double)NAN;
|
||||
vcmd.param7 = NAN;
|
||||
|
||||
Reference in New Issue
Block a user