mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: added RUDDER_ONLY parameter
this gives much easier setup for rudder only aircraft.
This commit is contained in:
parent
4fe39c67b4
commit
edec706c12
@ -968,7 +968,9 @@ static void set_servos(void)
|
|||||||
|
|
||||||
// send values to the PWM timers for output
|
// send values to the PWM timers for output
|
||||||
// ----------------------------------------
|
// ----------------------------------------
|
||||||
channel_roll->output();
|
if (g.rudder_only == 0) {
|
||||||
|
channel_roll->output();
|
||||||
|
}
|
||||||
channel_pitch->output();
|
channel_pitch->output();
|
||||||
channel_throttle->output();
|
channel_throttle->output();
|
||||||
channel_rudder->output();
|
channel_rudder->output();
|
||||||
|
@ -136,6 +136,7 @@ public:
|
|||||||
k_param_hil_mode,
|
k_param_hil_mode,
|
||||||
k_param_land_disarm_delay,
|
k_param_land_disarm_delay,
|
||||||
k_param_glide_slope_threshold,
|
k_param_glide_slope_threshold,
|
||||||
|
k_param_rudder_only,
|
||||||
|
|
||||||
// 100: Arming parameters
|
// 100: Arming parameters
|
||||||
k_param_arming = 100,
|
k_param_arming = 100,
|
||||||
@ -428,6 +429,7 @@ public:
|
|||||||
AP_Int8 mix_mode;
|
AP_Int8 mix_mode;
|
||||||
AP_Int8 vtail_output;
|
AP_Int8 vtail_output;
|
||||||
AP_Int8 elevon_output;
|
AP_Int8 elevon_output;
|
||||||
|
AP_Int8 rudder_only;
|
||||||
AP_Float mixing_gain;
|
AP_Float mixing_gain;
|
||||||
AP_Int8 reverse_elevons;
|
AP_Int8 reverse_elevons;
|
||||||
AP_Int8 reverse_ch1_elevon;
|
AP_Int8 reverse_ch1_elevon;
|
||||||
|
@ -757,6 +757,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: User
|
// @User: User
|
||||||
GSCALAR(mixing_gain, "MIXING_GAIN", 0.5f),
|
GSCALAR(mixing_gain, "MIXING_GAIN", 0.5f),
|
||||||
|
|
||||||
|
// @Param: RUDDER_ONLY
|
||||||
|
// @DisplayName: Rudder only aircraft
|
||||||
|
// @Description: Enable rudder only mode. The rudder will control attitude in attitude controlled modes (such as FBWA). You should setup your transmitter to send roll stick inputs to the RCMAP_YAW channel (normally channel 4). The rudder servo should be attached to the RCMAP_YAW channel as well. Note that automatic ground steering will be disabled for rudder only aircraft. You should also set KFF_RDDRMIX to 1.0. You will also need to setup the YAW2SRV_DAMP yaw damping appropriately for your aircraft. A value of 0.5 for YAW2SRV_DAMP is a good starting point.
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
|
// @User: User
|
||||||
|
GSCALAR(rudder_only, "RUDDER_ONLY", 0),
|
||||||
|
|
||||||
// @Param: SYS_NUM_RESETS
|
// @Param: SYS_NUM_RESETS
|
||||||
// @DisplayName: Num Resets
|
// @DisplayName: Num Resets
|
||||||
// @Description: Number of APM board resets
|
// @Description: Number of APM board resets
|
||||||
|
@ -90,7 +90,9 @@ void failsafe_check(void)
|
|||||||
channel_pitch->output();
|
channel_pitch->output();
|
||||||
}
|
}
|
||||||
channel_throttle->output();
|
channel_throttle->output();
|
||||||
channel_rudder->output();
|
if (g.rudder_only == 0) {
|
||||||
|
channel_rudder->output();
|
||||||
|
}
|
||||||
|
|
||||||
// setup secondary output channels that do have
|
// setup secondary output channels that do have
|
||||||
// corresponding input channels
|
// corresponding input channels
|
||||||
|
@ -8,7 +8,11 @@
|
|||||||
*/
|
*/
|
||||||
static void set_control_channels(void)
|
static void set_control_channels(void)
|
||||||
{
|
{
|
||||||
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
|
if (g.rudder_only) {
|
||||||
|
channel_roll = RC_Channel::rc_channel(rcmap.yaw()-1);
|
||||||
|
} else {
|
||||||
|
channel_roll = RC_Channel::rc_channel(rcmap.roll()-1);
|
||||||
|
}
|
||||||
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
|
channel_pitch = RC_Channel::rc_channel(rcmap.pitch()-1);
|
||||||
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
|
||||||
channel_rudder = RC_Channel::rc_channel(rcmap.yaw()-1);
|
channel_rudder = RC_Channel::rc_channel(rcmap.yaw()-1);
|
||||||
|
Loading…
Reference in New Issue
Block a user