mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-18 17:19:06 +08:00
added startup config for Maja and new generic mixer that uses channel 5 for wheel steering
This commit is contained in:
parent
ff57c809b8
commit
d015fbd678
@ -6,8 +6,8 @@
|
||||
#
|
||||
# @output MAIN1 aileron
|
||||
# @output MAIN2 elevator
|
||||
# @output MAIN4 rudder
|
||||
# @output MAIN3 throttle
|
||||
# @output MAIN3 rudder
|
||||
# @output MAIN4 throttle
|
||||
# @output MAIN5 flaps
|
||||
#
|
||||
# @output AUX1 feed-through of RC AUX1 channel
|
||||
|
||||
48
ROMFS/px4fmu_common/init.d/2105_maja
Normal file
48
ROMFS/px4fmu_common/init.d/2105_maja
Normal file
@ -0,0 +1,48 @@
|
||||
#!nsh
|
||||
#
|
||||
# @name Bormatec Maja
|
||||
#
|
||||
# @type Standard Plane
|
||||
#
|
||||
# @output MAIN1 aileron
|
||||
# @output MAIN2 elevator
|
||||
# @output MAIN3 rudder
|
||||
# @output MAIN4 throttle
|
||||
# @output MAIN5 wheel
|
||||
#
|
||||
# @output AUX1 feed-through of RC AUX1 channel
|
||||
# @output AUX2 feed-through of RC AUX2 channel
|
||||
# @output AUX3 feed-through of RC AUX3 channel
|
||||
#
|
||||
# @maintainer Andreas Antener <andreas@uaventure.com>
|
||||
#
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
if [ $AUTOCNF == yes ]
|
||||
then
|
||||
param set FW_AIRSPD_MIN 10
|
||||
param set FW_AIRSPD_TRIM 15
|
||||
param set FW_AIRSPD_MAX 20
|
||||
|
||||
param set FW_MAN_P_MAX 55
|
||||
param set FW_MAN_R_MAX 55
|
||||
param set FW_R_LIM 55
|
||||
|
||||
param set FW_WR_FF 0.2
|
||||
param set FW_WR_I 0.2
|
||||
param set FW_WR_IMAX 0.8
|
||||
param set FW_WR_P 1
|
||||
param set FW_W_RMAX 0
|
||||
|
||||
# set disarmed value for the ESC
|
||||
param set PWM_DISARMED 1000
|
||||
fi
|
||||
|
||||
set MIXER AERTW
|
||||
|
||||
# use PWM parameters for throttle channel
|
||||
set PWM_OUT 4
|
||||
set PWM_DISARMED p:PWM_DISARMED
|
||||
set PWM_MIN p:PWM_MIN
|
||||
set PWM_MAX p:PWM_MAX
|
||||
95
ROMFS/px4fmu_common/mixers/AERTW.main.mix
Normal file
95
ROMFS/px4fmu_common/mixers/AERTW.main.mix
Normal file
@ -0,0 +1,95 @@
|
||||
Aileron/rudder/elevator/throttle/wheel mixer for PX4FMU
|
||||
=======================================================
|
||||
|
||||
This file defines mixers suitable for controlling a fixed wing aircraft with
|
||||
aileron, rudder, elevator, throttle and steerable wheel controls using PX4FMU.
|
||||
The configuration assumes the aileron servo(s) are connected to PX4FMU servo
|
||||
output 0, the elevator to output 1, the rudder to output 2, the throttle
|
||||
to output 3 and the wheel to output 4.
|
||||
|
||||
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
|
||||
(roll), 1 (pitch), 2 (yaw) and 3 (thrust).
|
||||
|
||||
Aileron mixer
|
||||
-------------
|
||||
Two scalers total (output, roll).
|
||||
|
||||
This mixer assumes that the aileron servos are set up correctly mechanically;
|
||||
depending on the actual configuration it may be necessary to reverse the scaling
|
||||
factors (to reverse the servo movement) and adjust the offset, scaling and
|
||||
endpoints to suit.
|
||||
|
||||
As there is only one output, if using two servos adjustments to compensate for
|
||||
differences between the servos must be made mechanically. To obtain the correct
|
||||
motion using a Y cable, the servos can be positioned reversed from one another.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
|
||||
Elevator mixer
|
||||
------------
|
||||
Two scalers total (output, roll).
|
||||
|
||||
This mixer assumes that the elevator servo is set up correctly mechanically;
|
||||
depending on the actual configuration it may be necessary to reverse the scaling
|
||||
factors (to reverse the servo movement) and adjust the offset, scaling and
|
||||
endpoints to suit.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 1 -10000 -10000 0 -10000 10000
|
||||
|
||||
Rudder mixer
|
||||
------------
|
||||
Two scalers total (output, yaw).
|
||||
|
||||
This mixer assumes that the rudder servo is set up correctly mechanically;
|
||||
depending on the actual configuration it may be necessary to reverse the scaling
|
||||
factors (to reverse the servo movement) and adjust the offset, scaling and
|
||||
endpoints to suit.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 2 10000 10000 0 -10000 10000
|
||||
|
||||
Motor speed mixer
|
||||
-----------------
|
||||
Two scalers total (output, thrust).
|
||||
|
||||
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
|
||||
range. Inputs below zero are treated as zero.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
|
||||
Wheel mixer
|
||||
------------
|
||||
Two scalers total (output, yaw).
|
||||
|
||||
This mixer assumes that the wheel servo is set up correctly mechanically;
|
||||
depending on the actual configuration it may be necessary to reverse the scaling
|
||||
factors (to reverse the servo movement) and adjust the offset, scaling and
|
||||
endpoints to suit.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 2 10000 10000 0 -10000 10000
|
||||
|
||||
|
||||
Gimbal / flaps / payload mixer for last three channels,
|
||||
using the payload control group
|
||||
-----------------------------------------------------
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 2 0 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 2 1 10000 10000 0 -10000 10000
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 2 2 10000 10000 0 -10000 10000
|
||||
Loading…
x
Reference in New Issue
Block a user