mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
AP_MotorsMulticopter: output_to_motors and output_logic become protected
This commit is contained in:
parent
02881b59ff
commit
818965fa57
@ -42,9 +42,6 @@ public:
|
|||||||
// output_min - sends minimum values out to the motors
|
// output_min - sends minimum values out to the motors
|
||||||
void output_min();
|
void output_min();
|
||||||
|
|
||||||
// output_to_motors - sends commands to the motors
|
|
||||||
virtual void output_to_motors() = 0;
|
|
||||||
|
|
||||||
// set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
|
// set_yaw_headroom - set yaw headroom (yaw is given at least this amount of pwm)
|
||||||
void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; }
|
void set_yaw_headroom(int16_t pwm) { _yaw_headroom = pwm; }
|
||||||
|
|
||||||
@ -65,8 +62,6 @@ public:
|
|||||||
SPOOL_DOWN = 4, // decreasing maximum throttle while stabilizing
|
SPOOL_DOWN = 4, // decreasing maximum throttle while stabilizing
|
||||||
};
|
};
|
||||||
|
|
||||||
void output_logic();
|
|
||||||
|
|
||||||
// passes throttle directly to all motors for ESC calibration.
|
// passes throttle directly to all motors for ESC calibration.
|
||||||
// throttle_input is in the range of 0 ~ 1 where 0 will send get_pwm_output_min() and 1 will send get_pwm_output_max()
|
// throttle_input is in the range of 0 ~ 1 where 0 will send get_pwm_output_min() and 1 will send get_pwm_output_max()
|
||||||
void set_throttle_passthrough_for_esc_calibration(float throttle_input);
|
void set_throttle_passthrough_for_esc_calibration(float throttle_input);
|
||||||
@ -109,6 +104,12 @@ public:
|
|||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
// run spool logic
|
||||||
|
void output_logic();
|
||||||
|
|
||||||
|
// output_to_motors - sends commands to the motors
|
||||||
|
virtual void output_to_motors() = 0;
|
||||||
|
|
||||||
// update the throttle input filter
|
// update the throttle input filter
|
||||||
virtual void update_throttle_filter();
|
virtual void update_throttle_filter();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user