mavlink: avoid 'stream xy not found' warnings on CONSTRAINED_FLASH targets

e.g.:
WARN  [mavlink] stream ADSB_VEHICLE not found
WARN  [mavlink] stream GIMBAL_DEVICE_ATTITUDE_STATUS not found
WARN  [mavlink] stream GIMBAL_MANAGER_STATUS not found
WARN  [mavlink] stream GIMBAL_DEVICE_SET_ATTITUDE not found
WARN  [mavlink] stream GPS2_RAW not found
WARN  [mavlink] stream UTM_GLOBAL_POSITION not found
ERROR [mavlink] configure_streams_to_default() failed
This commit is contained in:
Beat Küng 2021-05-11 14:37:17 +02:00 committed by Daniel Agar
parent 9e352e92bd
commit 2a84afb6a2
1 changed files with 4 additions and 1 deletions

View File

@ -1213,9 +1213,12 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
}
/* if we reach here, the stream list does not contain the stream */
#if defined(CONSTRAINED_FLASH) // flash constrained target's don't include all streams
return PX4_OK;
#else
PX4_WARN("stream %s not found", stream_name);
return PX4_ERROR;
#endif
}
void