mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Motors: make output_armed() and output_disarmed() pure virtual
This commit is contained in:
parent
70855027f3
commit
0e53c0a892
@ -198,8 +198,8 @@ public:
|
||||
protected:
|
||||
|
||||
// output functions that should be overloaded by child classes
|
||||
virtual void output_armed() {};
|
||||
virtual void output_disarmed() {};
|
||||
virtual void output_armed()=0;
|
||||
virtual void output_disarmed()=0;
|
||||
|
||||
// update_max_throttle - updates the limits on _max_throttle for slow_start and current limiting flag
|
||||
void update_max_throttle();
|
||||
|
Loading…
Reference in New Issue
Block a user