Disable debug in the airspeed sensor driver - prevents console spam if it fails (and on probing during startup)

This commit is contained in:
Lorenz Meier 2014-01-24 17:26:13 +01:00
parent d8c1131f1e
commit 65118f0c2e
1 changed files with 1 additions and 1 deletions

View File

@ -91,7 +91,7 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) :
_comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors"))
{
// enable debug() calls
_debug_enabled = true;
_debug_enabled = false;
// work_cancel in the dtor will explode if we don't do this...
memset(&_work, 0, sizeof(_work));