@ -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()
@ -421,7 +421,7 @@ RCInput_RPI::~RCInput_RPI()
delete con_blocks;
}
void RCInput_RPI::deinit()
void RCInput_RPI::teardown()
{
stop_dma();
@ -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;
};
@ -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);