mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-08 18:52:46 +08:00
MAVLink: Fix rate handling for camera trigger messages
This commit is contained in:
@@ -1407,6 +1407,11 @@ public:
|
||||
return new MavlinkStreamCameraTrigger(mavlink);
|
||||
}
|
||||
|
||||
virtual bool const_rate()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
unsigned get_size()
|
||||
{
|
||||
return (_trigger_time > 0) ? MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
|
||||
|
||||
Reference in New Issue
Block a user