AP_MotorsMatrix: init to virtual and remove duplicate set initalised

This commit is contained in:
Peter Hall 2021-01-26 19:03:53 +00:00 committed by Randy Mackay
parent 1395f9ce79
commit cc26a520bc
2 changed files with 1 additions and 3 deletions

View File

@ -89,8 +89,6 @@ bool AP_MotorsMatrix::init(uint8_t expected_num_motors)
set_update_rate(_speed_hz);
set_initialised_ok(true);
return true;
}
#endif // ENABLE_SCRIPTING

View File

@ -34,7 +34,7 @@ public:
#ifdef ENABLE_SCRIPTING
// Init to be called from scripting
bool init(uint8_t expected_num_motors);
virtual bool init(uint8_t expected_num_motors);
#endif // ENABLE_SCRIPTING
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)