mirror of https://github.com/ArduPilot/ardupilot
autotest: added support for vtail testing in runsim
virtual vtail support
This commit is contained in:
parent
777c6a308e
commit
fe6e83f7f2
|
@ -75,6 +75,14 @@ def process_sitl_input(buf):
|
|||
# the minus does away with the need for RC2_REV=-1
|
||||
elevator = -(ch2+ch1)/2.0
|
||||
|
||||
if opts.vtail:
|
||||
# fake an elevon plane
|
||||
ch1 = elevator
|
||||
ch2 = rudder
|
||||
# this matches VTAIL_OUTPUT==2
|
||||
elevator = (ch2-ch1)/2.0
|
||||
rudder = (ch2+ch1)/2.0
|
||||
|
||||
if aileron != sitl_state.aileron:
|
||||
jsb_set('fcs/aileron-cmd-norm', aileron)
|
||||
sitl_state.aileron = aileron
|
||||
|
@ -147,6 +155,7 @@ parser.add_option("--home", type='string', help="home lat,lng,alt,hdg (requir
|
|||
parser.add_option("--script", type='string', help='jsbsim model script', default='jsbsim/rascal_test.xml')
|
||||
parser.add_option("--options", type='string', help='jsbsim startup options')
|
||||
parser.add_option("--elevon", action='store_true', default=False, help='assume elevon input')
|
||||
parser.add_option("--vtail", action='store_true', default=False, help='assume vtail input')
|
||||
parser.add_option("--wind", dest="wind", help="Simulate wind (speed,direction,turbulance)", default='0,0,0')
|
||||
|
||||
(opts, args) = parser.parse_args()
|
||||
|
|
|
@ -0,0 +1,33 @@
|
|||
#!/bin/bash
|
||||
|
||||
killall -q JSBSim
|
||||
killall -q ArduPlane.elf
|
||||
pkill -f runsim.py
|
||||
|
||||
set -e
|
||||
set -x
|
||||
|
||||
autotest=$(dirname $(readlink -e $0))
|
||||
pushd $autotest/../../ArduPlane
|
||||
make clean sitl
|
||||
|
||||
tfile=$(mktemp)
|
||||
echo r > $tfile
|
||||
#gnome-terminal -e "gdb -x $tfile --args /tmp/ArduPlane.build/ArduPlane.elf"
|
||||
gnome-terminal -e /tmp/ArduPlane.build/ArduPlane.elf
|
||||
#gnome-terminal -e "valgrind -q /tmp/ArduPlane.build/ArduPlane.elf"
|
||||
sleep 2
|
||||
rm -f $tfile
|
||||
gnome-terminal -e '../Tools/autotest/jsbsim/runsim.py --home=-35.362938,149.165085,584,270 --vtail'
|
||||
sleep 2
|
||||
popd
|
||||
|
||||
# if you wanted to forward packets out a serial link for testing
|
||||
# andropilot, then add --out /dev/serial/by-id/usb-FTDI* to your
|
||||
# command line along with a baudrate. You might also like to add --map
|
||||
# and --console
|
||||
# for example:
|
||||
# sim_arduplane.sh --out /dev/serial/by-id/usb-FTDI* --baudrate 57600 --map --console
|
||||
|
||||
mavproxy.py --master tcp:127.0.0.1:5760 --sitl 127.0.0.1:5501 --out 127.0.0.1:14550 --out 127.0.0.1:14551 $*
|
||||
|
Loading…
Reference in New Issue