AP_Motors: update notify

This commit is contained in:
Randy Mackay 2013-08-08 22:15:04 +09:00 committed by Andrew Tridgell
parent ac36a09747
commit f8a872f01e
2 changed files with 8 additions and 1 deletions

View File

@ -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)
{

View File

@ -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);