mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
feat(actuators): Control Flaps from AUX channel (#26913)
* feat(rc): flaps via AUX channel * docs(actuators): add flaps and spoilers from RC Co-authored-by: Silvan Fuhrer <silvan@auterion.com> * docs(actuators): Update docs/en/payloads/generic_actuator_control.md Co-authored-by: Hamish Willee <hamishwillee@gmail.com> * docs(actuators): move flaps setup docs --------- Co-authored-by: Silvan Fuhrer <silvan@auterion.com> Co-authored-by: Hamish Willee <hamishwillee@gmail.com>
This commit is contained in:
parent
0b621009d5
commit
76eca4b7a4
@ -175,7 +175,7 @@ The fields are:
|
||||
|
||||
#### Flap Scale and Spoiler Scale Configuration
|
||||
|
||||
"Flap-control" and "Spoiler-control" are aerodynamic configurations that can either be commanded manually by the pilot (using RC, say), or are set automatically by the controller.
|
||||
"Flap-control" and "Spoiler-control" are aerodynamic configurations that can either be commanded manually by the pilot (using RC or a Joystick, say) (see [Flaps and Spoiler Control with Manual Control](#flaps-and-spoiler-control-with-manual-control)), or are set automatically by the controller.
|
||||
For example, a pilot or the landing system might engage "Spoiler-control" in order to reduce the airspeed before landing.
|
||||
|
||||
The configurations are an _abstract_ way for the controller to tell the allocator how much it should adjust the aerodynamic properties of the wings relative to the "full flaps" or "full spoiler" configuration (between `[0,1]`, where "1" indicates the full range).
|
||||
@ -198,6 +198,20 @@ In the following example, the vehicle has two ailerons, one elevator, one rudder
|
||||
These are the elevator deflections added to compensate for the pitching moments generated by the flaps and spoiler actuators.
|
||||
In the case here the elevator would be deflected 0.3 up when the flaps are fully deployed to counteract the pitching down moment caused by the flaps.
|
||||
|
||||
#### Flaps and Spoiler Control with Manual Control
|
||||
|
||||
The preferred method to manually actuate spoilers and flaps is to map a manual control switch to an `AUX` output (see [Generic Actuator Control with RC](#generic-actuator-control-with-rc)), and then map that AUX output to the flap or spoiler function using [FW_FLAPS_MAN](../advanced_config/parameter_reference.md#FW_FLAPS_MAN) or [FW_SPOILERS_MAN](../advanced_config/parameter_reference.md#FW_SPOILERS_MAN).
|
||||
The source for the manual control can be RC or MAVLink.
|
||||
|
||||
::: warning
|
||||
The following method is not recommended, and will be removed in a future release.
|
||||
If using it you should migrate to using the AUX-based method.
|
||||
|
||||
It is also possible to define a flaps channel directly on the RC using [RC_MAP_FLAPS](../advanced_config/parameter_reference.md#RC_MAP_FLAPS).
|
||||
This channel can also be used to control the spoilers by setting [FW_SPOILERS_MAN](../advanced_config/parameter_reference.md#FW_SPOILERS_MAN) to `Flaps channel`.
|
||||
This method is not possible when the source for the manual control is MAVLink.
|
||||
:::
|
||||
|
||||
#### Actuator Roll, Pitch, and Yaw Scaling
|
||||
|
||||
::: info
|
||||
|
||||
@ -35,6 +35,7 @@ To map a particular RC channel to an output function `RC AUX n` (and hence it's
|
||||
For example, to control an actuator attached to AUX pin 3 (say) you would assign the output function `RC AUX 5` to the output `AUX3`.
|
||||
You could then use set the RC channel to control the `AUX3` output using `RC_MAP_AUX5`.
|
||||
|
||||
|
||||
## Generic Actuator Control in Missions
|
||||
|
||||
To use generic actuator control in a mission you must first [configure the outputs that you want to control using MAVLink](#generic-actuator-control-with-mavlink).
|
||||
|
||||
@ -469,9 +469,35 @@ void FixedwingRateControl::Run()
|
||||
// Flaps control
|
||||
float flaps_control = 0.f; // default to no flaps
|
||||
|
||||
/* map flaps by default to manual if valid */
|
||||
if (PX4_ISFINITE(_manual_control_setpoint.flaps)) {
|
||||
flaps_control = math::max(_manual_control_setpoint.flaps, 0.f); // do not consider negative switch settings
|
||||
switch (_param_fw_flaps_man.get()) { // do not consider negative switch settings
|
||||
case 0:
|
||||
break;
|
||||
|
||||
case 1:
|
||||
flaps_control = PX4_ISFINITE(_manual_control_setpoint.aux1) ? math::max(_manual_control_setpoint.aux1, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
flaps_control = PX4_ISFINITE(_manual_control_setpoint.aux2) ? math::max(_manual_control_setpoint.aux2, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
flaps_control = PX4_ISFINITE(_manual_control_setpoint.aux3) ? math::max(_manual_control_setpoint.aux3, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
flaps_control = PX4_ISFINITE(_manual_control_setpoint.aux4) ? math::max(_manual_control_setpoint.aux4, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 5:
|
||||
flaps_control = PX4_ISFINITE(_manual_control_setpoint.aux5) ? math::max(_manual_control_setpoint.aux5, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 6:
|
||||
flaps_control = PX4_ISFINITE(_manual_control_setpoint.flaps) ? math::max(_manual_control_setpoint.flaps, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
|
||||
}
|
||||
|
||||
normalized_unsigned_setpoint_s flaps_setpoint;
|
||||
@ -482,19 +508,29 @@ void FixedwingRateControl::Run()
|
||||
// Spoilers control
|
||||
float spoilers_control = 0.f; // default to no spoilers
|
||||
|
||||
switch (_param_fw_spoilers_man.get()) {
|
||||
switch (_param_fw_spoilers_man.get()) { // do not consider negative switch settings
|
||||
case 0:
|
||||
break;
|
||||
|
||||
case 1:
|
||||
// do not consider negative switch settings
|
||||
spoilers_control = PX4_ISFINITE(_manual_control_setpoint.flaps) ? math::max(_manual_control_setpoint.flaps, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
// do not consider negative switch settings
|
||||
spoilers_control = PX4_ISFINITE(_manual_control_setpoint.aux1) ? math::max(_manual_control_setpoint.aux1, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
spoilers_control = PX4_ISFINITE(_manual_control_setpoint.aux2) ? math::max(_manual_control_setpoint.aux2, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
spoilers_control = PX4_ISFINITE(_manual_control_setpoint.aux3) ? math::max(_manual_control_setpoint.aux3, 0.f) : 0.f;
|
||||
break;
|
||||
|
||||
case 5:
|
||||
spoilers_control = PX4_ISFINITE(_manual_control_setpoint.aux4) ? math::max(_manual_control_setpoint.aux4, 0.f) : 0.f;
|
||||
break;
|
||||
}
|
||||
|
||||
normalized_unsigned_setpoint_s spoilers_setpoint;
|
||||
|
||||
@ -213,7 +213,8 @@ private:
|
||||
(ParamFloat<px4::params::TRIM_ROLL>) _param_trim_roll,
|
||||
(ParamFloat<px4::params::TRIM_YAW>) _param_trim_yaw,
|
||||
|
||||
(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man
|
||||
(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man,
|
||||
(ParamInt<px4::params::FW_FLAPS_MAN>) _param_fw_flaps_man
|
||||
)
|
||||
|
||||
RateControl _rate_control; ///< class for rate control calculations
|
||||
|
||||
@ -326,6 +326,24 @@ parameters:
|
||||
0: Disabled
|
||||
1: Flaps channel
|
||||
2: Aux1
|
||||
3: Aux2
|
||||
4: Aux3
|
||||
5: Aux4
|
||||
6: Aux5
|
||||
default: 0
|
||||
FW_FLAPS_MAN:
|
||||
description:
|
||||
short: Flap input in manual flight
|
||||
long: Chose source for manual setting of flaps in manual flight modes.
|
||||
type: enum
|
||||
values:
|
||||
0: Disabled
|
||||
1: Aux1
|
||||
2: Aux2
|
||||
3: Aux3
|
||||
4: Aux4
|
||||
5: Aux5
|
||||
6: Flaps channel
|
||||
default: 0
|
||||
FW_ACRO_YAW_EN:
|
||||
description:
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user