uavcan rtcm set max num injections

This commit is contained in:
alexklimaj 2023-05-15 20:17:21 -06:00 committed by Julian Oes
parent acd19a0520
commit 5b8ae69f47

View File

@ -467,11 +467,11 @@ void UavcanGnssBridge::update()
// to work.
void UavcanGnssBridge::handleInjectDataTopic()
{
// Limit maximum number of GPS injections to 6 since usually
// Limit maximum number of GPS injections to 8 since usually
// GPS injections should consist of 1-4 packets (GPS, Glonass, BeiDou, Galileo).
// Looking at 6 packets thus guarantees, that at least a full injection
// data set is evaluated.
static constexpr size_t MAX_NUM_INJECTIONS = 6;
static constexpr size_t MAX_NUM_INJECTIONS = gps_inject_data_s::ORB_QUEUE_LENGTH;;
size_t num_injections = 0;
gps_inject_data_s gps_inject_data;