mirror of https://github.com/ArduPilot/ardupilot
parent
17f2f40b11
commit
80a1688361
|
@ -26,6 +26,9 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// singleton instance
|
||||
AP_Motors *AP_Motors::_instance;
|
||||
|
||||
// Constructor
|
||||
AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
||||
_loop_rate(loop_rate),
|
||||
|
@ -40,6 +43,8 @@ AP_Motors::AP_Motors(uint16_t loop_rate, uint16_t speed_hz) :
|
|||
_air_density_ratio(1.0f),
|
||||
_motor_fast_mask(0)
|
||||
{
|
||||
_instance = this;
|
||||
|
||||
// init other flags
|
||||
_flags.armed = false;
|
||||
_flags.interlock = false;
|
||||
|
|
|
@ -59,6 +59,9 @@ public:
|
|||
// Constructor
|
||||
AP_Motors(uint16_t loop_rate, uint16_t speed_hz = AP_MOTORS_SPEED_DEFAULT);
|
||||
|
||||
// singleton support
|
||||
static AP_Motors *get_instance(void) { return _instance; }
|
||||
|
||||
// check initialisation succeeded
|
||||
bool initialised_ok() const { return _flags.initialised_ok; }
|
||||
|
||||
|
@ -207,10 +210,13 @@ protected:
|
|||
uint16_t _motor_fast_mask;
|
||||
|
||||
// pass through variables
|
||||
float _roll_radio_passthrough = 0.0f; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||
float _pitch_radio_passthrough = 0.0f; // pitch input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||
float _throttle_radio_passthrough = 0.0f; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed
|
||||
float _yaw_radio_passthrough = 0.0f; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||
float _roll_radio_passthrough; // roll input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||
float _pitch_radio_passthrough; // pitch input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||
float _throttle_radio_passthrough; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed
|
||||
float _yaw_radio_passthrough; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
|
||||
|
||||
AP_Int8 _pwm_type; // PWM output type
|
||||
|
||||
private:
|
||||
static AP_Motors *_instance;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue