MotorsHeli: minor formatting updates

This commit is contained in:
Randy Mackay 2016-12-12 19:23:35 +09:00
parent a09d4db4fd
commit 2da7ea746b
2 changed files with 6 additions and 8 deletions

View File

@ -65,7 +65,6 @@ public:
void Init();
// set update rate to motors - a value in hertz
// you must have setup_motors before calling this
virtual void set_update_rate( uint16_t speed_hz ) = 0;
// enable - starts allowing signals to be sent to motors
@ -77,7 +76,7 @@ public:
// 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
virtual void output_test(uint8_t motor_seq, int16_t pwm) = 0;
virtual void output_test(uint8_t motor_seq, int16_t pwm) = 0;
//
// heli specific methods
@ -118,7 +117,7 @@ public:
virtual uint16_t get_motor_mask() = 0;
// output - sends commands to the motors
void output();
void output();
// supports_yaw_passthrough
virtual bool supports_yaw_passthrough() const { return false; }
@ -141,9 +140,9 @@ protected:
};
// output - sends commands to the motors
void output_armed_stabilizing();
void output_armed_zero_throttle();
void output_disarmed();
void output_armed_stabilizing();
void output_armed_zero_throttle();
void output_disarmed();
// update_motor_controls - sends commands to motor controllers
virtual void update_motor_control(RotorControlState state) = 0;
@ -152,7 +151,7 @@ protected:
void reset_flight_controls();
// update the throttle input filter
void update_throttle_filter();
void update_throttle_filter();
// move_actuators - moves swash plate and tail rotor
virtual void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) = 0;

View File

@ -55,7 +55,6 @@ public:
};
// set update rate to motors - a value in hertz
// you must have setup_motors before calling this
void set_update_rate(uint16_t speed_hz);
// enable - starts allowing signals to be sent to motors and servos