mirror of https://github.com/ArduPilot/ardupilot
AP_MotorsMulticopter: add roll, pitch, throttle and yaw pass through
This commit is contained in:
parent
d7c27c949c
commit
06f25b669d
|
@ -554,3 +554,12 @@ void AP_MotorsMulticopter::throttle_pass_through(int16_t pwm)
|
||||||
hal.rcout->push();
|
hal.rcout->push();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// set_radio_passthrough used to pass radio inputs directly to outputs
|
||||||
|
void AP_MotorsMulticopter::set_radio_passthrough(float radio_roll_input, float radio_pitch_input, float radio_throttle_input, float radio_yaw_input)
|
||||||
|
{
|
||||||
|
_roll_radio_passthrough = radio_roll_input;
|
||||||
|
_pitch_radio_passthrough = radio_pitch_input;
|
||||||
|
_throttle_radio_passthrough = radio_throttle_input;
|
||||||
|
_yaw_radio_passthrough = radio_yaw_input;
|
||||||
|
}
|
||||||
|
|
|
@ -173,6 +173,9 @@ protected:
|
||||||
// spin when armed as a percentage of the 0~1 range from 0 to throttle_min
|
// spin when armed as a percentage of the 0~1 range from 0 to throttle_min
|
||||||
float spin_when_armed_low_end_pct() { return (float)_spin_when_armed.get() / _min_throttle; }
|
float spin_when_armed_low_end_pct() { return (float)_spin_when_armed.get() / _min_throttle; }
|
||||||
|
|
||||||
|
// spin when armed as a percentage of the 0~1 range from 0 to throttle_min
|
||||||
|
void set_radio_passthrough(float radio_roll_input, float radio_pitch_input, float radio_throttle_input, float radio_yaw_input);
|
||||||
|
|
||||||
// flag bitmask
|
// flag bitmask
|
||||||
struct {
|
struct {
|
||||||
spool_up_down_mode spool_mode : 4; // motor's current spool mode
|
spool_up_down_mode spool_mode : 4; // motor's current spool mode
|
||||||
|
@ -214,4 +217,10 @@ protected:
|
||||||
int16_t _batt_timer; // timer used in battery resistance calcs
|
int16_t _batt_timer; // timer used in battery resistance calcs
|
||||||
float _lift_max; // maximum lift ratio from battery voltage
|
float _lift_max; // maximum lift ratio from battery voltage
|
||||||
float _throttle_limit; // ratio of throttle limit between hover and maximum
|
float _throttle_limit; // ratio of throttle limit between hover and maximum
|
||||||
|
|
||||||
|
// pass through variables
|
||||||
|
float _roll_radio_passthrough = 0; // roll control PWM direct from radio, used for manual control
|
||||||
|
float _pitch_radio_passthrough = 0; // pitch control PWM direct from radio, used for manual control
|
||||||
|
float _throttle_radio_passthrough = 0; // throttle control PWM direct from radio, used for manual control
|
||||||
|
float _yaw_radio_passthrough = 0; // yaw control PWM direct from radio, used for manual control
|
||||||
};
|
};
|
||||||
|
|
Loading…
Reference in New Issue