AP_Motors: remove multicopter only features

Also rename uses of Multirotor to Multicopter
This commit is contained in:
Randy Mackay 2015-07-13 13:39:57 +09:00
parent e3a0f1568d
commit c9dedbd3b2
3 changed files with 19 additions and 114 deletions

View File

@ -4,6 +4,7 @@
#define __AP_MOTORS_H__ #define __AP_MOTORS_H__
#include "AP_Motors_Class.h" #include "AP_Motors_Class.h"
#include "AP_MotorsMulticopter.h"
#include "AP_MotorsMatrix.h" #include "AP_MotorsMatrix.h"
#include "AP_MotorsTri.h" #include "AP_MotorsTri.h"
#include "AP_MotorsQuad.h" #include "AP_MotorsQuad.h"

View File

@ -38,23 +38,12 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
_speed_hz(speed_hz), _speed_hz(speed_hz),
_throttle_radio_min(1100), _throttle_radio_min(1100),
_throttle_radio_max(1900), _throttle_radio_max(1900),
_spin_when_armed_ramped(0),
_batt_voltage(0.0f),
_batt_voltage_resting(0.0f),
_batt_current(0.0f),
_batt_current_resting(0.0f),
_batt_resistance(0.0f),
_batt_timer(0),
_air_density_ratio(1.0f),
_lift_max(1.0f),
_throttle_limit(1.0f),
_throttle_in(0.0f), _throttle_in(0.0f),
_throttle_filter() _throttle_filter(),
_batt_voltage(0.0f),
_batt_current(0.0f),
_air_density_ratio(1.0f)
{ {
// slow start motors from zero to min throttle
_flags.slow_start = true;
_flags.slow_start_low_end = true;
// init other flags // init other flags
_flags.armed = false; _flags.armed = false;
_flags.stabilizing = false; _flags.stabilizing = false;
@ -75,8 +64,5 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
void AP_Motors::armed(bool arm) void AP_Motors::armed(bool arm)
{ {
_flags.armed = arm; _flags.armed = arm;
if (!_flags.armed) {
_flags.slow_start_low_end = true;
}
AP_Notify::flags.armed = arm; AP_Notify::flags.armed = arm;
}; };

View File

@ -24,10 +24,6 @@
#define AP_MOTORS_MAX_NUM_MOTORS 8 #define AP_MOTORS_MAX_NUM_MOTORS 8
#define AP_MOTORS_DEFAULT_MIN_THROTTLE 130
#define AP_MOTORS_DEFAULT_MID_THROTTLE 500
#define AP_MOTORS_DEFAULT_MAX_THROTTLE 1000
// frame definitions // frame definitions
#define AP_MOTORS_PLUS_FRAME 0 #define AP_MOTORS_PLUS_FRAME 0
#define AP_MOTORS_X_FRAME 1 #define AP_MOTORS_X_FRAME 1
@ -43,17 +39,6 @@
// motor update rate // motor update rate
#define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors #define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
#define THROTTLE_CURVE_ENABLED 1 // throttle curve disabled by default
#define THROTTLE_CURVE_MID_THRUST 52 // throttle which produces 1/2 the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
#define THROTTLE_CURVE_MAX_THRUST 93 // throttle which produces the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
// bit mask for recording which limits we have reached when outputting to motors
#define AP_MOTOR_NO_LIMITS_REACHED 0x00
#define AP_MOTOR_ROLLPITCH_LIMIT 0x01
#define AP_MOTOR_YAW_LIMIT 0x02
#define AP_MOTOR_THROTTLE_LIMIT 0x04
#define AP_MOTOR_ANY_LIMIT 0xFF
/// @class AP_Motors /// @class AP_Motors
class AP_Motors { class AP_Motors {
public: public:
@ -77,20 +62,6 @@ public:
// get motor interlock status. true means motors run, false motors don't run // get motor interlock status. true means motors run, false motors don't run
bool get_interlock() const { return _flags.interlock; }; bool get_interlock() const { return _flags.interlock; };
// set_throttle_range - 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)
// also sets throttle channel minimum and maximum pwm
virtual void set_throttle_range(uint16_t min_throttle, int16_t radio_min, int16_t radio_max) {}
// set_hover_throttle - sets the mid throttle which is close to the hover throttle of the copter
// this is used to limit the amount that the stability patch will increase the throttle to give more room for roll, pitch and yaw control
void set_hover_throttle(uint16_t hov_thr) { _hover_out = hov_thr; }
// get_hover_throttle_as_pwm - converts hover throttle to pwm (i.e. range 1000 ~ 2000)
int16_t get_hover_throttle_as_pwm() const;
int16_t throttle_min() const { return rel_pwm_to_thr_range(_min_throttle); }
int16_t throttle_max() const { return _max_throttle;}
// set_roll, set_pitch, set_yaw, set_throttle // set_roll, set_pitch, set_yaw, set_throttle
void set_roll(int16_t roll_in) { _roll_control_input = roll_in; }; // range -4500 ~ 4500 void set_roll(int16_t roll_in) { _roll_control_input = roll_in; }; // range -4500 ~ 4500
void set_pitch(int16_t pitch_in) { _pitch_control_input = pitch_in; }; // range -4500 ~ 4500 void set_pitch(int16_t pitch_in) { _pitch_control_input = pitch_in; }; // range -4500 ~ 4500
@ -106,30 +77,18 @@ public:
void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(filt_hz); } void set_throttle_filter_cutoff(float filt_hz) { _throttle_filter.set_cutoff_frequency(filt_hz); }
//
// voltage, current and air pressure compensation or limiting features - multicopters only
//
// set_voltage - set voltage to be used for output scaling // set_voltage - set voltage to be used for output scaling
virtual void set_voltage(float volts){ _batt_voltage = volts; } void set_voltage(float volts){ _batt_voltage = volts; }
// set_current - set current to be used for output scaling // set_current - set current to be used for output scaling
virtual void set_current(float current){ _batt_current = current; } void set_current(float current){ _batt_current = current; }
// set_density_ratio - sets air density as a proportion of sea level density // set_density_ratio - sets air density as a proportion of sea level density
void set_air_density_ratio(float ratio) { _air_density_ratio = ratio; } void set_air_density_ratio(float ratio) { _air_density_ratio = ratio; }
// get_lift_max - get maximum lift ratio
float get_lift_max() { return _lift_max; }
// get_batt_voltage_filt - get battery voltage ratio
float get_batt_voltage_filt() { return _batt_voltage_filt.get(); }
// get_batt_resistance - get battery resistance approximation
float get_batt_resistance() { return _batt_resistance; }
// get_throttle_limit - throttle limit ratio
float get_throttle_limit() { return _throttle_limit; }
// 1 if motor is enabled, 0 otherwise
bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS];
// structure for holding motor limit flags // structure for holding motor limit flags
struct AP_Motors_limit { struct AP_Motors_limit {
uint8_t roll_pitch : 1; // we have reached roll or pitch limit uint8_t roll_pitch : 1; // we have reached roll or pitch limit
@ -138,13 +97,12 @@ public:
uint8_t throttle_upper : 1; // we have reached throttle's upper limit uint8_t throttle_upper : 1; // we have reached throttle's upper limit
} limit; } limit;
//////////////////////////////////////////////////////////////////////// //
// Virtual Functions to be overloaded by child classes // virtual functions that should be implemented by child classes
// in most cases this is done because of global usage of multirotor specific //
// functions which do not apply to helicopters
// init // init
virtual void Init() {} virtual void Init() = 0;
// enable - starts allowing signals to be sent to motors // enable - starts allowing signals to be sent to motors
virtual void enable() = 0; virtual void enable() = 0;
@ -160,30 +118,9 @@ public:
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 // 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;
virtual int16_t throttle_min() { return AP_MOTORS_DEFAULT_MIN_THROTTLE;};
virtual int16_t throttle_max() { return AP_MOTORS_DEFAULT_MAX_THROTTLE;};
// set_hover_throttle - sets the mid throttle which is close to the hover throttle of the copter
// this is used to limit the amount that the stability patch will increase the throttle to give more room for roll, pitch and yaw control
virtual void set_hover_throttle(uint16_t hov_thr) {}
// throttle_pass_through - passes provided pwm directly to all motors - dangerous but used for initialising ESCs
// pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000
virtual void throttle_pass_through(int16_t pwm) {}
// returns warning throttle
virtual float get_throttle_warn() { return 0; }
// set_throttle_thr_mix - set desired throttle_thr_mix (actual throttle_thr_mix is slewed towards this value over 1~2 seconds)
// low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
// has no effect when throttle is above hover throttle
virtual void set_throttle_mix_min() {}
virtual void set_throttle_mix_mid() {}
virtual void set_throttle_mix_max() {}
// slow_start - set to true to slew motors from current speed to maximum // slow_start - set to true to slew motors from current speed to maximum
// Note: this must be set immediately before a step up in throttle // Note: this must be set immediately before a step up in throttle
virtual void slow_start(bool true_false) {}; virtual void slow_start(bool true_false) = 0;
// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used) // get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict // this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
@ -199,22 +136,11 @@ protected:
// update the throttle input filter // update the throttle input filter
virtual void update_throttle_filter() = 0; virtual void update_throttle_filter() = 0;
// convert RPY and Throttle servo ranges from legacy controller scheme back into PWM values
// RPY channels typically +/-45 degrees servo travel between +/-400 PWM
// Throttle channel typically 0-1000 range converts to 1100-1900 PWM for final output signal to motors
// ToDo: this should all be handled as floats +/- 1.0 instead of PWM and fake angle ranges
int16_t calc_roll_pwm() { return (_roll_control_input / 11.25f);}
int16_t calc_pitch_pwm() { return (_pitch_control_input / 11.25f);}
int16_t calc_yaw_pwm() { return (_yaw_control_input / 11.25f);}
int16_t calc_throttle_radio_output() { return (_throttle_control_input * _throttle_pwm_scalar) + _throttle_radio_min;}
// flag bitmask // flag bitmask
struct AP_Motors_flags { struct AP_Motors_flags {
uint8_t armed : 1; // 0 if disarmed, 1 if armed uint8_t armed : 1; // 0 if disarmed, 1 if armed
uint8_t stabilizing : 1; // 0 if not controlling attitude, 1 if controlling attitude uint8_t stabilizing : 1; // 0 if not controlling attitude, 1 if controlling attitude
uint8_t frame_orientation : 4; // PLUS_FRAME 0, X_FRAME 1, V_FRAME 2, H_FRAME 3, NEW_PLUS_FRAME 10, NEW_X_FRAME, NEW_V_FRAME, NEW_H_FRAME uint8_t frame_orientation : 4; // PLUS_FRAME 0, X_FRAME 1, V_FRAME 2, H_FRAME 3, NEW_PLUS_FRAME 10, NEW_X_FRAME, NEW_V_FRAME, NEW_H_FRAME
uint8_t slow_start : 1; // 1 if slow start is active
uint8_t slow_start_low_end : 1; // 1 just after arming so we can ramp up the spin_when_armed value
uint8_t interlock : 1; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run) uint8_t interlock : 1; // 1 if the motor interlock is enabled (i.e. motors run), 0 if disabled (motors don't run)
} _flags; } _flags;
@ -231,20 +157,12 @@ protected:
uint16_t _speed_hz; // speed in hz to send updates to motors uint16_t _speed_hz; // speed in hz to send updates to motors
int16_t _throttle_radio_min; // minimum radio channel pwm int16_t _throttle_radio_min; // minimum radio channel pwm
int16_t _throttle_radio_max; // maximum radio channel pwm int16_t _throttle_radio_max; // maximum radio channel pwm
int16_t _spin_when_armed_ramped; // equal to _spin_when_armed parameter but slowly ramped up from zero float _throttle_in; // last throttle input from set_throttle caller
LowPassFilterFloat _throttle_filter; // throttle input filter
// battery voltage compensation variables // battery voltage, current and air pressure compensation variables
float _batt_voltage; // latest battery voltage reading float _batt_voltage; // latest battery voltage reading
float _batt_voltage_resting; // battery voltage reading at minimum throttle
LowPassFilterFloat _batt_voltage_filt; // filtered battery voltage expressed as a percentage (0 ~ 1.0) of batt_voltage_max
float _batt_current; // latest battery current reading float _batt_current; // latest battery current reading
float _batt_current_resting; // battery's current when motors at minimum
float _batt_resistance; // battery's resistance calculated by comparing resting voltage vs in flight voltage
int16_t _batt_timer; // timer used in battery resistance calcs
float _air_density_ratio; // air density / sea level density - decreases in altitude float _air_density_ratio; // air density / sea level density - decreases in altitude
float _lift_max; // maximum lift ratio from battery voltage
float _throttle_limit; // ratio of throttle limit between hover and maximum
float _throttle_in; // last throttle input from set_throttle caller
LowPassFilterFloat _throttle_filter; // throttle input filter
}; };
#endif // __AP_MOTORS_CLASS_H__ #endif // __AP_MOTORS_CLASS_H__