mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Motors: add output_to_motors
This commit is contained in:
parent
ac579685df
commit
c96b91efb6
@ -114,6 +114,9 @@ public:
|
||||
// output_min - sends minimum values out to the motors
|
||||
virtual void output_min() = 0;
|
||||
|
||||
// output_to_motors - sends minimum values out to the motors
|
||||
virtual void output_to_motors() = 0;
|
||||
|
||||
// output_test - spin a motor at the pwm value specified
|
||||
// motor_seq is the motor's sequence number from 1 to the number of motors on the frame
|
||||
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
|
||||
@ -131,7 +134,6 @@ protected:
|
||||
// output functions that should be overloaded by child classes
|
||||
virtual void output_armed_stabilizing()=0;
|
||||
virtual void output_armed_zero_throttle() { output_min(); }
|
||||
virtual void output_disarmed()=0;
|
||||
virtual void rc_write(uint8_t chan, uint16_t pwm);
|
||||
virtual void rc_set_freq(uint32_t mask, uint16_t freq_hz);
|
||||
virtual void rc_enable_ch(uint8_t chan);
|
||||
|
Loading…
Reference in New Issue
Block a user