AP_MotorsHeli: use AP_Motors set_radio_passthrough in 0 to 1 range

This commit is contained in:
Randy Mackay 2016-02-03 20:57:44 +09:00
parent 68a6408a23
commit e863f0b9c0
2 changed files with 5 additions and 21 deletions

View File

@ -254,7 +254,7 @@ void AP_MotorsHeli::output_disarmed()
// pass pilot commands straight through to swash
_roll_in = _roll_radio_passthrough;
_pitch_in = _pitch_radio_passthrough;
_throttle_filter.reset(_throttle_radio_passthrough / 1000.0f);
_throttle_filter.reset(_throttle_radio_passthrough);
_yaw_in = _yaw_radio_passthrough;
break;
case SERVO_CONTROL_MODE_MANUAL_CENTER:
@ -355,22 +355,13 @@ void AP_MotorsHeli::update_throttle_filter()
_throttle_filter.apply(_throttle_in, 1.0f/_loop_rate);
}
// set_radio_passthrough used to pass radio inputs directly to outputs
void AP_MotorsHeli::set_radio_passthrough(int16_t radio_roll_input, int16_t radio_pitch_input, int16_t radio_throttle_input, int16_t 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;
}
// reset_radio_passthrough used to reset all radio inputs to center
void AP_MotorsHeli::reset_radio_passthrough()
{
_roll_radio_passthrough = 0;
_pitch_radio_passthrough = 0;
_throttle_radio_passthrough = 500;
_yaw_radio_passthrough = 0;
_roll_radio_passthrough = 0.0f;
_pitch_radio_passthrough = 0.0f;
_throttle_radio_passthrough = 0.5f;
_yaw_radio_passthrough = 0.0f;
}
// reset_flight_controls - resets all controls and scalars to flight status

View File

@ -131,9 +131,6 @@ public:
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
virtual uint16_t get_motor_mask() = 0;
// set_radio_passthrough used to pass radio inputs directly to outputs
void set_radio_passthrough(int16_t radio_roll_input, int16_t radio_pitch_input, int16_t radio_throttle_input, int16_t radio_yaw_input);
// reset_radio_passthrough used to reset all radio inputs to center
void reset_radio_passthrough();
@ -213,9 +210,5 @@ protected:
float _pitchFactor[AP_MOTORS_HELI_NUM_SWASHPLATE_SERVOS];
float _collectiveFactor[AP_MOTORS_HELI_NUM_SWASHPLATE_SERVOS];
int16_t _collective_mid_pwm = 0; // collective mid parameter value converted to pwm form (i.e. 0 ~ 1000)
int16_t _roll_radio_passthrough = 0; // roll control PWM direct from radio, used for manual control
int16_t _pitch_radio_passthrough = 0; // pitch control PWM direct from radio, used for manual control
int16_t _throttle_radio_passthrough = 0; // throttle control PWM direct from radio, used for manual control
int16_t _yaw_radio_passthrough = 0; // yaw control PWM direct from radio, used for manual control
uint8_t _servo_test_cycle_counter = 0; // number of test cycles left to run after bootup
};