Browse Source

MAVLink: Fix rate handling for camera trigger messages

sbg
Lorenz Meier 8 years ago
parent
commit
c84611f0f5
  1. 5
      src/modules/mavlink/mavlink_messages.cpp

5
src/modules/mavlink/mavlink_messages.cpp

@ -1407,6 +1407,11 @@ public: @@ -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;

Loading…
Cancel
Save