mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: update notify
This commit is contained in:
parent
ac36a09747
commit
f8a872f01e
|
@ -81,6 +81,12 @@ void AP_Motors::Init()
|
|||
setup_throttle_curve();
|
||||
};
|
||||
|
||||
void AP_Motors::armed(bool arm)
|
||||
{
|
||||
_armed = arm;
|
||||
notify.flags.armed = _armed;
|
||||
};
|
||||
|
||||
// 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)
|
||||
void AP_Motors::set_min_throttle(uint16_t min_throttle)
|
||||
{
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
#include <AP_Common.h>
|
||||
#include <AP_Progmem.h>
|
||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||
#include <AP_Notify.h> // Notify library
|
||||
#include <AP_Curve.h> // Curve used to linearlise throttle pwm to thrust
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
|
||||
|
@ -87,7 +88,7 @@ public:
|
|||
|
||||
// arm, disarm or check status status of motors
|
||||
bool armed() { return _armed; };
|
||||
void armed(bool arm) { _armed = 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)
|
||||
void set_min_throttle(uint16_t min_throttle);
|
||||
|
|
Loading…
Reference in New Issue