uncrustify libraries/AP_Motors/AP_Motors.h

This commit is contained in:
uncrustify 2012-08-16 23:20:27 -07:00 committed by Pat Hickey
parent 4fe97c1e7b
commit d773a9c43b
1 changed files with 97 additions and 71 deletions

View File

@ -54,7 +54,8 @@ public:
AP_Motors( uint8_t APM_version, APM_RC_Class* rc_out, RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_throttle, RC_Channel* rc_yaw, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
// init
virtual void Init() {};
virtual void Init() {
};
// set mapping from motor number to RC channel
virtual void set_motor_to_channel_map( uint8_t mot_1, uint8_t mot_2, uint8_t mot_3, uint8_t mot_4, uint8_t mot_5, uint8_t mot_6, uint8_t mot_7, uint8_t mot_8 ) {
@ -69,38 +70,61 @@ public:
}
// set update rate to motors - a value in hertz or AP_MOTORS_SPEED_INSTANT_PWM for instant pwm
virtual void set_update_rate( uint16_t speed_hz ) { _speed_hz = speed_hz; };
virtual void set_update_rate( uint16_t speed_hz ) {
_speed_hz = speed_hz;
};
// set frame orientation (normally + or X)
virtual void set_frame_orientation( uint8_t new_orientation ) { _frame_orientation = new_orientation; };
virtual void set_frame_orientation( uint8_t new_orientation ) {
_frame_orientation = new_orientation;
};
// enable - starts allowing signals to be sent to motors
virtual void enable() {};
virtual void enable() {
};
// arm, disarm or check status status of motors
virtual bool armed() { return _armed; };
virtual void armed(bool arm) { _armed = arm; };
virtual bool armed() {
return _armed;
};
virtual void armed(bool arm) {
_armed = arm;
};
// check or set status of auto_armed - controls whether autopilot can take control of throttle
// Note: this should probably be moved out of this class as it has little to do with the motors
virtual bool auto_armed() { return _auto_armed; };
virtual void auto_armed(bool arm) { _auto_armed = arm; };
virtual bool auto_armed() {
return _auto_armed;
};
virtual void auto_armed(bool arm) {
_auto_armed = arm;
};
// set_min_throttle - sets the minimum throttle that will be sent to the engines when they're not off (i.e. to prevents issues with some motors spinning and some not at very low throttle)
virtual void set_min_throttle(uint16_t min_throttle) { _min_throttle = min_throttle; };
virtual void set_max_throttle(uint16_t max_throttle) { _max_throttle = max_throttle; };
virtual void set_min_throttle(uint16_t min_throttle) {
_min_throttle = min_throttle;
};
virtual void set_max_throttle(uint16_t max_throttle) {
_max_throttle = max_throttle;
};
// output - sends commands to the motors
virtual void output() { if( _armed && _auto_armed ) { output_armed(); }else{ output_disarmed(); } };
virtual void output() {
if( _armed && _auto_armed ) { output_armed(); }else{ output_disarmed(); }
};
// output_min - sends minimum values out to the motors
virtual void output_min() {};
virtual void output_min() {
};
// get basic information about the platform
virtual uint8_t get_num_motors() { return 0; };
virtual uint8_t get_num_motors() {
return 0;
};
// motor test
virtual void output_test() {};
virtual void output_test() {
};
// throttle_pass_through - passes throttle through to motors - dangerous but required for initialising ESCs
virtual void throttle_pass_through();
@ -120,8 +144,10 @@ public:
protected:
// output functions that should be overloaded by child classes
virtual void output_armed() {};
virtual void output_disarmed() {};
virtual void output_armed() {
};
virtual void output_disarmed() {
};
APM_RC_Class* _rc; // APM_RC class used to send updates to ESCs/Servos
RC_Channel* _rc_roll, *_rc_pitch, *_rc_throttle, *_rc_yaw; // input in from users