Browse Source

AP_HAL: RCInput: rename deinit() to teardown()

master
Lucas De Marchi 8 years ago
parent
commit
312a27dd20
  1. 2
      libraries/AP_HAL/RCInput.h
  2. 2
      libraries/AP_HAL_Linux/RCInput_RPI.cpp
  3. 2
      libraries/AP_HAL_Linux/RCInput_RPI.h
  4. 2
      libraries/AP_HAL_Linux/system.cpp

2
libraries/AP_HAL/RCInput.h

@ -14,7 +14,7 @@ public: @@ -14,7 +14,7 @@ public:
* in the C++ type system.)
*/
virtual void init() = 0;
virtual void deinit() {};
virtual void teardown() {};
/**
* Return true if there has been new input since the last read()

2
libraries/AP_HAL_Linux/RCInput_RPI.cpp

@ -421,7 +421,7 @@ RCInput_RPI::~RCInput_RPI() @@ -421,7 +421,7 @@ RCInput_RPI::~RCInput_RPI()
delete con_blocks;
}
void RCInput_RPI::deinit()
void RCInput_RPI::teardown()
{
stop_dma();
}

2
libraries/AP_HAL_Linux/RCInput_RPI.h

@ -127,7 +127,7 @@ private: @@ -127,7 +127,7 @@ private:
static void termination_handler(int signum);
void set_sigaction();
void set_physical_addresses(int version);
void deinit() override;
void teardown() override;
};
}

2
libraries/AP_HAL_Linux/system.cpp

@ -30,7 +30,7 @@ void panic(const char *errormsg, ...) @@ -30,7 +30,7 @@ void panic(const char *errormsg, ...)
va_end(ap);
UNUSED_RESULT(write(1, "\n", 1));
hal.rcin->deinit();
hal.rcin->teardown();
hal.scheduler->delay_microseconds(10000);
exit(1);
}

Loading…
Cancel
Save