|
|
@ -44,7 +44,9 @@ enum ioevents { |
|
|
|
|
|
|
|
|
|
|
|
AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) : |
|
|
|
AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) : |
|
|
|
uart(_uart) |
|
|
|
uart(_uart) |
|
|
|
{} |
|
|
|
{ |
|
|
|
|
|
|
|
singleton = this; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
#define IOMCU_DEBUG_ENABLE 0 |
|
|
|
#define IOMCU_DEBUG_ENABLE 0 |
|
|
|
|
|
|
|
|
|
|
@ -54,6 +56,8 @@ AP_IOMCU::AP_IOMCU(AP_HAL::UARTDriver &_uart) : |
|
|
|
#define debug(fmt, args ...) |
|
|
|
#define debug(fmt, args ...) |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
AP_IOMCU *AP_IOMCU::singleton; |
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
/*
|
|
|
|
initialise library, starting thread |
|
|
|
initialise library, starting thread |
|
|
|
*/ |
|
|
|
*/ |
|
|
@ -999,4 +1003,11 @@ void AP_IOMCU::check_iomcu_reset(void) |
|
|
|
trigger_event(IOEVENT_SET_DEFAULT_RATE); |
|
|
|
trigger_event(IOEVENT_SET_DEFAULT_RATE); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
namespace AP { |
|
|
|
|
|
|
|
AP_IOMCU *iomcu(void) { |
|
|
|
|
|
|
|
return AP_IOMCU::get_singleton(); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
|
|
#endif // HAL_WITH_IO_MCU
|
|
|
|
#endif // HAL_WITH_IO_MCU
|
|
|
|