mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
AP_Motors: move some functions to protected
Also minor formatting fix
This commit is contained in:
parent
13ad06e652
commit
41189758b8
@ -40,18 +40,6 @@ public:
|
|||||||
// output_to_motors - sends minimum values out to the motors
|
// output_to_motors - sends minimum values out to the motors
|
||||||
void output_to_motors();
|
void output_to_motors();
|
||||||
|
|
||||||
// add_motor using just position and yaw_factor (or prop direction)
|
|
||||||
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);
|
|
||||||
|
|
||||||
// add_motor using separate roll and pitch factors (for asymmetrical frames) and prop direction
|
|
||||||
void add_motor(int8_t motor_num, float roll_factor_in_degrees, float pitch_factor_in_degrees, float yaw_factor, uint8_t testing_order);
|
|
||||||
|
|
||||||
// remove_motor
|
|
||||||
void remove_motor(int8_t motor_num);
|
|
||||||
|
|
||||||
// remove_all_motors - removes all motor definitions
|
|
||||||
void remove_all_motors();
|
|
||||||
|
|
||||||
// setup_motors - configures the motors for a given frame type - should be overwritten by child classes
|
// setup_motors - configures the motors for a given frame type - should be overwritten by child classes
|
||||||
virtual void setup_motors() { remove_all_motors(); };
|
virtual void setup_motors() { remove_all_motors(); };
|
||||||
|
|
||||||
@ -66,6 +54,15 @@ protected:
|
|||||||
// add_motor using raw roll, pitch, throttle and yaw factors
|
// add_motor using raw roll, pitch, throttle and yaw factors
|
||||||
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
|
void add_motor_raw(int8_t motor_num, float roll_fac, float pitch_fac, float yaw_fac, uint8_t testing_order);
|
||||||
|
|
||||||
|
// add_motor using just position and yaw_factor (or prop direction)
|
||||||
|
void add_motor(int8_t motor_num, float angle_degrees, float yaw_factor, uint8_t testing_order);
|
||||||
|
|
||||||
|
// add_motor using separate roll and pitch factors (for asymmetrical frames) and prop direction
|
||||||
|
void add_motor(int8_t motor_num, float roll_factor_in_degrees, float pitch_factor_in_degrees, float yaw_factor, uint8_t testing_order);
|
||||||
|
|
||||||
|
// remove_motor
|
||||||
|
void remove_motor(int8_t motor_num);
|
||||||
|
|
||||||
// normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
|
// normalizes the roll, pitch and yaw factors so maximum magnitude is 0.5
|
||||||
void normalise_rpy_factors();
|
void normalise_rpy_factors();
|
||||||
|
|
||||||
|
@ -41,9 +41,6 @@ public:
|
|||||||
// Constructor
|
// Constructor
|
||||||
AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
||||||
|
|
||||||
// set update rate to motors - a value in hertz
|
|
||||||
virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; }
|
|
||||||
|
|
||||||
// set frame orientation (normally + or X)
|
// set frame orientation (normally + or X)
|
||||||
virtual void set_frame_orientation( uint8_t new_orientation ) { _flags.frame_orientation = new_orientation; }
|
virtual void set_frame_orientation( uint8_t new_orientation ) { _flags.frame_orientation = new_orientation; }
|
||||||
|
|
||||||
@ -107,6 +104,9 @@ public:
|
|||||||
// virtual functions that should be implemented by child classes
|
// virtual functions that should be implemented by child classes
|
||||||
//
|
//
|
||||||
|
|
||||||
|
// set update rate to motors - a value in hertz
|
||||||
|
virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; }
|
||||||
|
|
||||||
// init
|
// init
|
||||||
virtual void Init() = 0;
|
virtual void Init() = 0;
|
||||||
|
|
||||||
@ -149,7 +149,7 @@ protected:
|
|||||||
void add_motor_num(int8_t motor_num);
|
void add_motor_num(int8_t motor_num);
|
||||||
|
|
||||||
// update the throttle input filter
|
// update the throttle input filter
|
||||||
virtual void update_throttle_filter() = 0;
|
virtual void update_throttle_filter() = 0;
|
||||||
|
|
||||||
// save parameters as part of disarming
|
// save parameters as part of disarming
|
||||||
virtual void save_params_on_disarm() {}
|
virtual void save_params_on_disarm() {}
|
||||||
|
Loading…
Reference in New Issue
Block a user