mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: make motors armed call const
This commit is contained in:
parent
3b0de0d23d
commit
48a0917670
@ -95,7 +95,7 @@ public:
|
|||||||
virtual void enable() = 0;
|
virtual void enable() = 0;
|
||||||
|
|
||||||
// arm, disarm or check status status of motors
|
// arm, disarm or check status status of motors
|
||||||
bool armed() { return _flags.armed; };
|
bool armed() const { return _flags.armed; };
|
||||||
void armed(bool arm);
|
void armed(bool arm);
|
||||||
|
|
||||||
// set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
|
// set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
|
||||||
|
Loading…
Reference in New Issue
Block a user