diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index 2e4a284..c578ea8 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -227,10 +227,10 @@ void roscontroller::RosControllerRun() const uint8_t shrt_id= 0xFF; float result; - if ( GetFilteredPacketLoss(shrt_id, result) ) - log<