Browse Source

AP_MotorsMulticopter: promote output_min from Matrix class

mission-4.1.18
Randy Mackay 9 years ago
parent
commit
b4b33db79b
  1. 8
      libraries/AP_Motors/AP_MotorsMulticopter.cpp
  2. 3
      libraries/AP_Motors/AP_MotorsMulticopter.h

8
libraries/AP_Motors/AP_MotorsMulticopter.cpp

@ -149,6 +149,14 @@ void AP_MotorsMulticopter::output() @@ -149,6 +149,14 @@ void AP_MotorsMulticopter::output()
output_to_motors();
};
// sends minimum values out to the motors
void AP_MotorsMulticopter::output_min()
{
set_desired_spool_state(DESIRED_SHUT_DOWN);
_multicopter_flags.spool_mode = SHUT_DOWN;
output();
}
// update the throttle input filter
void AP_MotorsMulticopter::update_throttle_filter()
{

3
libraries/AP_Motors/AP_MotorsMulticopter.h

@ -40,6 +40,9 @@ public: @@ -40,6 +40,9 @@ public:
// output - sends commands to the motors
virtual void output();
// output_min - sends minimum values out to the motors
void output_min();
// output_to_motors - sends commands to the motors
virtual void output_to_motors() = 0;

Loading…
Cancel
Save