MAVLink: Fix rate handling for camera trigger messages

This commit is contained in:
Lorenz Meier 2017-05-18 10:19:12 +02:00
parent ee637952ba
commit c84611f0f5
1 changed files with 5 additions and 0 deletions

View File

@ -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;