mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_MotorsMatrix: init to virtual and remove duplicate set initalised
This commit is contained in:
parent
1395f9ce79
commit
cc26a520bc
@ -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
|
||||
|
@ -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)
|
||||
|
Loading…
Reference in New Issue
Block a user