AP_RangeFinder: mark _add_backend, init and detetct_instance as __INITFUNC__

This commit is contained in:
Peter Barker 2025-03-01 09:37:55 +11:00 committed by Thomas Watson
parent e68be1cdb9
commit 75be83954a

View File

@ -203,7 +203,7 @@ void RangeFinder::convert_params(void)
finders here. For now we won't allow for hot-plugging of finders here. For now we won't allow for hot-plugging of
rangefinders. rangefinders.
*/ */
void RangeFinder::init(enum Rotation orientation_default) __INITFUNC__ void RangeFinder::init(enum Rotation orientation_default)
{ {
convert_params(); convert_params();
@ -260,7 +260,7 @@ void RangeFinder::update(void)
#endif #endif
} }
bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend, uint8_t instance, uint8_t serial_instance) __INITFUNC__ bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend, uint8_t instance, uint8_t serial_instance)
{ {
if (!backend) { if (!backend) {
return false; return false;
@ -282,7 +282,7 @@ bool RangeFinder::_add_backend(AP_RangeFinder_Backend *backend, uint8_t instance
/* /*
detect if an instance of a rangefinder is connected. detect if an instance of a rangefinder is connected.
*/ */
void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) __INITFUNC__ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance)
{ {
AP_RangeFinder_Backend_Serial *(*serial_create_fn)(RangeFinder::RangeFinder_State&, AP_RangeFinder_Params&) = nullptr; AP_RangeFinder_Backend_Serial *(*serial_create_fn)(RangeFinder::RangeFinder_State&, AP_RangeFinder_Params&) = nullptr;