mirror of https://github.com/ArduPilot/ardupilot
Tools: move SITL on HW to Tools and simplify config
This commit is contained in:
parent
0a060aa520
commit
30d71e42df
|
@ -0,0 +1,80 @@
|
||||||
|
# SITL-on-HW notes
|
||||||
|
|
||||||
|
## Compiling and flashing
|
||||||
|
|
||||||
|
Run the sitl-on-hw.sh script to compile and flash for MatekH743. Adjust for your own board if required before running. This script will configure a build ready for running SITL-on-hardware and attempt to upload it to a connected board. It includes a set of embedded parameters to configure the simulated sensors appropriately.
|
||||||
|
|
||||||
|
::
|
||||||
|
|
||||||
|
cd $HOME/ardupilot
|
||||||
|
./libraries/SITL/examples/on-hardware/sitl-on-hw.py --board MatekH743 --vehicle copter
|
||||||
|
|
||||||
|
Plane can also be simulated:
|
||||||
|
|
||||||
|
::
|
||||||
|
|
||||||
|
cd $HOME/ardupilot
|
||||||
|
./libraries/SITL/examples/on-hardware/sitl-on-hw.py --board MatekH743 --vehicle plane
|
||||||
|
|
||||||
|
and quadplane:
|
||||||
|
|
||||||
|
::
|
||||||
|
|
||||||
|
cd $HOME/ardupilot
|
||||||
|
./libraries/SITL/examples/on-hardware/sitl-on-hw.py --board MatekH743 --vehicle plane --simclass QuadPlane
|
||||||
|
|
||||||
|
## Configuring
|
||||||
|
|
||||||
|
Wipe the parameters on the board; this can be done with a mavlink command, or by setting the FORMAT_VERSION parameter to 0.
|
||||||
|
|
||||||
|
For example:
|
||||||
|
|
||||||
|
::
|
||||||
|
|
||||||
|
STABILIZE> wipe_parameters IREALLYMEAANIT
|
||||||
|
STABILIZE> Got COMMAND_ACK: PREFLIGHT_STORAGE: ACCEPTED
|
||||||
|
AP: All parameters reset, reboot board
|
||||||
|
reboot
|
||||||
|
|
||||||
|
You may need to power-cycle the board at this point.
|
||||||
|
|
||||||
|
::
|
||||||
|
|
||||||
|
Device /dev/serial/by-id/usb-ArduPilot_MatekH743_3A0019001051393036353035-if00 reopened OK
|
||||||
|
link 1 OK
|
||||||
|
heartbeat OK
|
||||||
|
disabling flow control on serial 2
|
||||||
|
AP: Calibrating barometer
|
||||||
|
AP: Barometer 1 calibration complete
|
||||||
|
AP: Barometer 2 calibration complete
|
||||||
|
Init Gyro**
|
||||||
|
AP: ArduPilot Ready
|
||||||
|
Suggested EK3_BCOEF_* = 16.288, EK3_MCOEF = 0.208
|
||||||
|
Home: -35.36326 149.1652 alt=584.0000m hdg=353.0000
|
||||||
|
Smoothing reset at 0.001
|
||||||
|
AP: RCOut: PWM:1-13
|
||||||
|
AP: GPS 1: detected as SITL at 115200 baud
|
||||||
|
Time has wrapped
|
||||||
|
Time has wrapped 5577 368458
|
||||||
|
AP: EKF3 IMU0 initialised
|
||||||
|
AP: EKF3 IMU1 initialised
|
||||||
|
AP: EKF3 IMU0 tilt alignment complete
|
||||||
|
AP: EKF3 IMU1 tilt alignment complete
|
||||||
|
AP: EKF3 IMU1 MAG0 initial yaw alignment complete
|
||||||
|
AP: EKF3 IMU0 MAG0 initial yaw alignment complete
|
||||||
|
AP: PERF: 0/3999 [2653:2349] F=400Hz sd=39 Ex=0
|
||||||
|
AP: EKF3 IMU1 forced reset
|
||||||
|
AP: EKF3 IMU1 initialised
|
||||||
|
AP: EKF3 IMU0 forced reset
|
||||||
|
AP: EKF3 IMU0 initialised
|
||||||
|
AP: EKF3 IMU1 tilt alignment complete
|
||||||
|
AP: EKF3 IMU0 tilt alignment complete
|
||||||
|
AP: EKF3 IMU1 MAG0 initial yaw alignment complete
|
||||||
|
AP: EKF3 IMU0 MAG0 initial yaw alignment complete
|
||||||
|
AP: PreArm: 3D Accel calibration needed
|
||||||
|
AP: PERF: 0/4000 [2631:2369] F=400Hz sd=5 Ex=0
|
||||||
|
AP: EKF3 IMU0 origin set
|
||||||
|
AP: EKF3 IMU1 origin set
|
||||||
|
AP: PERF: 0/4000 [2639:2362] F=400Hz sd=7 Ex=0
|
||||||
|
|
||||||
|
Force
|
|
@ -0,0 +1,28 @@
|
||||||
|
AHRS_EKF_TYPE 10
|
||||||
|
|
||||||
|
GPS_TYPE 100
|
||||||
|
|
||||||
|
INS_ACCOFFS_X 0.001
|
||||||
|
INS_ACCOFFS_Y 0.001
|
||||||
|
INS_ACCOFFS_Z 0.001
|
||||||
|
INS_ACCSCAL_X 1.001
|
||||||
|
INS_ACCSCAL_Y 1.001
|
||||||
|
INS_ACCSCAL_Z 1.001
|
||||||
|
INS_ACC2OFFS_X 0.001
|
||||||
|
INS_ACC2OFFS_Y 0.001
|
||||||
|
INS_ACC2OFFS_Z 0.001
|
||||||
|
INS_ACC2SCAL_X 1.001
|
||||||
|
INS_ACC2SCAL_Y 1.001
|
||||||
|
INS_ACC2SCAL_Z 1.001
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
SIM_MAG1_DEVID 97539
|
||||||
|
|
||||||
|
|
||||||
|
SIM_RATE_HZ 400
|
||||||
|
SCHED_LOOP_RATE 400
|
||||||
|
|
||||||
|
BRD_RTC_TYPES 2
|
||||||
|
BRD_HEAT_TARG 25
|
||||||
|
BRD_SAFETY_DEFLT 0
|
|
@ -0,0 +1,36 @@
|
||||||
|
env SIM_ENABLED 1
|
||||||
|
|
||||||
|
define INS_MAX_INSTANCES 2
|
||||||
|
define HAL_COMPASS_MAX_SENSORS 2
|
||||||
|
|
||||||
|
define AP_GPS_BACKEND_DEFAULT_ENABLED 0
|
||||||
|
define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0
|
||||||
|
|
||||||
|
define HAL_NAVEKF2_AVAILABLE 0
|
||||||
|
define EK3_FEATURE_BODY_ODOM 0
|
||||||
|
define EK3_FEATURE_EXTERNAL_NAV 0
|
||||||
|
define EK3_FEATURE_DRAG_FUSION 0
|
||||||
|
define HAL_ADSB_ENABLED 0
|
||||||
|
define HAL_PROXIMITY_ENABLED 0
|
||||||
|
define HAL_VISUALODOM_ENABLED 0
|
||||||
|
define HAL_GENERATOR_ENABLED 0
|
||||||
|
|
||||||
|
define MODE_SPORT_ENABLED 0
|
||||||
|
define MODE_THROW_ENABLED 0
|
||||||
|
define MODE_TURTLE_ENABLED 0
|
||||||
|
define MODE_FLOWHOLD 0
|
||||||
|
define MODE_POSHOLD_ENABLED 0
|
||||||
|
define MODE_SYSTEMID_ENABLED 0
|
||||||
|
define MODE_ACRO_ENABLED 0
|
||||||
|
define MODE_FOLLOW_ENABLED 0
|
||||||
|
define MODE_FLIP_ENABLED 0
|
||||||
|
define MODE_DRIFT_ENABLED 0
|
||||||
|
define MODE_THROW_ENABLED 0
|
||||||
|
|
||||||
|
|
||||||
|
define HAL_MSP_OPTICALFLOW_ENABLED 0
|
||||||
|
define HAL_SUPPORT_RCOUT_SERIAL 0
|
||||||
|
define HAL_HOTT_TELEM_ENABLED 0
|
||||||
|
define HAL_HIGH_LATENCY2 0
|
||||||
|
|
||||||
|
define AP_SIM_INS_FILE_ENABLED 0
|
|
@ -0,0 +1,30 @@
|
||||||
|
AHRS_EKF_TYPE 10
|
||||||
|
|
||||||
|
GPS_TYPE 100
|
||||||
|
|
||||||
|
INS_ACCOFFS_X 0.001
|
||||||
|
INS_ACCOFFS_Y 0.001
|
||||||
|
INS_ACCOFFS_Z 0.001
|
||||||
|
INS_ACCSCAL_X 1.001
|
||||||
|
INS_ACCSCAL_Y 1.001
|
||||||
|
INS_ACCSCAL_Z 1.001
|
||||||
|
INS_ACC2OFFS_X 0.001
|
||||||
|
INS_ACC2OFFS_Y 0.001
|
||||||
|
INS_ACC2OFFS_Z 0.001
|
||||||
|
INS_ACC2SCAL_X 1.001
|
||||||
|
INS_ACC2SCAL_Y 1.001
|
||||||
|
INS_ACC2SCAL_Z 1.001
|
||||||
|
|
||||||
|
|
||||||
|
SIM_MAG1_DEVID 97539
|
||||||
|
|
||||||
|
|
||||||
|
SIM_RATE_HZ 400
|
||||||
|
SCHED_LOOP_RATE 400
|
||||||
|
|
||||||
|
BRD_RTC_TYPES 2
|
||||||
|
BRD_HEAT_TARG 25
|
||||||
|
BRD_SAFETY_DEFLT 0
|
||||||
|
|
||||||
|
SERVO3_MIN 1000
|
||||||
|
SERVO3_MAX 2000
|
|
@ -0,0 +1,23 @@
|
||||||
|
env SIM_ENABLED 1
|
||||||
|
|
||||||
|
define INS_MAX_INSTANCES 2
|
||||||
|
define HAL_COMPASS_MAX_SENSORS 2
|
||||||
|
|
||||||
|
define AP_GPS_BACKEND_DEFAULT_ENABLED 0
|
||||||
|
define AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED 0
|
||||||
|
|
||||||
|
define HAL_NAVEKF2_AVAILABLE 0
|
||||||
|
define EK3_FEATURE_BODY_ODOM 0
|
||||||
|
define EK3_FEATURE_EXTERNAL_NAV 0
|
||||||
|
define EK3_FEATURE_DRAG_FUSION 0
|
||||||
|
define HAL_ADSB_ENABLED 0
|
||||||
|
define HAL_PROXIMITY_ENABLED 0
|
||||||
|
define HAL_VISUALODOM_ENABLED 0
|
||||||
|
define HAL_GENERATOR_ENABLED 0
|
||||||
|
|
||||||
|
define HAL_MSP_OPTICALFLOW_ENABLED 0
|
||||||
|
define HAL_SUPPORT_RCOUT_SERIAL 0
|
||||||
|
define HAL_HOTT_TELEM_ENABLED 0
|
||||||
|
define HAL_HIGH_LATENCY2 0
|
||||||
|
|
||||||
|
define AP_SIM_INS_FILE_ENABLED 0
|
|
@ -0,0 +1,91 @@
|
||||||
|
#!/usr/bin/env python3
|
||||||
|
'''
|
||||||
|
script to build a firmware for SITL-on-hardware
|
||||||
|
see https://ardupilot.org/dev/docs/sim-on-hardware.html
|
||||||
|
'''
|
||||||
|
|
||||||
|
import subprocess
|
||||||
|
import sys
|
||||||
|
import os
|
||||||
|
import tempfile
|
||||||
|
|
||||||
|
from argparse import ArgumentParser
|
||||||
|
parser = ArgumentParser("SITL on hardware builder")
|
||||||
|
parser.add_argument("--board", default=None, help="board type")
|
||||||
|
parser.add_argument("--vehicle", default=None, help="vehicle type")
|
||||||
|
parser.add_argument("--frame", default=None, help="frame type")
|
||||||
|
parser.add_argument("--simclass", default=None, help="simulation class")
|
||||||
|
parser.add_argument("--defaults", default=None, help="extra defaults file")
|
||||||
|
parser.add_argument("--upload", action='store_true', default=False, help="upload firmware")
|
||||||
|
|
||||||
|
args, unknown_args = parser.parse_known_args()
|
||||||
|
|
||||||
|
extra_hwdef = None
|
||||||
|
|
||||||
|
def run_program(cmd_list):
|
||||||
|
'''run a program from a command list'''
|
||||||
|
print("Running (%s)" % " ".join(cmd_list))
|
||||||
|
retcode = subprocess.call(cmd_list)
|
||||||
|
if retcode != 0:
|
||||||
|
print("FAILED: %s" % (' '.join(cmd_list)))
|
||||||
|
global extra_hwdef
|
||||||
|
if extra_hwdef is not None:
|
||||||
|
extra_hwdef.close()
|
||||||
|
os.unlink(extra_hwdef.name)
|
||||||
|
sys.exit(1)
|
||||||
|
|
||||||
|
extra_hwdef = tempfile.NamedTemporaryFile(mode='w')
|
||||||
|
extra_defaults = tempfile.NamedTemporaryFile(mode='w')
|
||||||
|
|
||||||
|
def hwdef_write(s):
|
||||||
|
'''write to the hwdef temp file'''
|
||||||
|
extra_hwdef.write(s)
|
||||||
|
|
||||||
|
def defaults_write(s):
|
||||||
|
'''write to the hwdef temp file'''
|
||||||
|
extra_defaults.write(s)
|
||||||
|
|
||||||
|
def sohw_path(fname):
|
||||||
|
'''get path to a file in on-hardware directory'''
|
||||||
|
return os.path.join(os.path.dirname(os.path.realpath(__file__)), fname)
|
||||||
|
|
||||||
|
if args.vehicle == "plane":
|
||||||
|
extra_hwdef_base = "plane-extra-hwdef-sitl-on-hw.dat"
|
||||||
|
defaults_base = "plane-default.param"
|
||||||
|
else:
|
||||||
|
extra_hwdef_base = "extra-hwdef-sitl-on-hw.dat"
|
||||||
|
defaults_base = "default.param"
|
||||||
|
|
||||||
|
# add base hwdef to extra_hwdef
|
||||||
|
hwdef_write(open(sohw_path(extra_hwdef_base), "r").read() + "\n")
|
||||||
|
|
||||||
|
# add base defaults to extra_defaults
|
||||||
|
defaults_write(open(sohw_path(defaults_base), "r").read() + "\n")
|
||||||
|
|
||||||
|
if args.defaults:
|
||||||
|
defaults_write(open(args.defaults,"r").read() + "\n")
|
||||||
|
|
||||||
|
if args.simclass:
|
||||||
|
hwdef_write("define AP_SIM_FRAME_CLASS %s\n" % args.simclass)
|
||||||
|
if args.frame:
|
||||||
|
hwdef_write('define AP_SIM_FRAME_STRING "%s"\n' % args.frame)
|
||||||
|
|
||||||
|
extra_hwdef.flush()
|
||||||
|
extra_defaults.flush()
|
||||||
|
|
||||||
|
configure_args = ["./waf", "configure",
|
||||||
|
"--board=%s" % args.board,
|
||||||
|
"--extra-hwdef=%s" % extra_hwdef.name,
|
||||||
|
"--default-param=%s" % extra_defaults.name]
|
||||||
|
configure_args.extend(unknown_args)
|
||||||
|
run_program(configure_args)
|
||||||
|
|
||||||
|
build_cmd = ["./waf", args.vehicle]
|
||||||
|
if args.upload:
|
||||||
|
build_cmd.append("--upload")
|
||||||
|
|
||||||
|
run_program(build_cmd)
|
||||||
|
|
||||||
|
# cleanup
|
||||||
|
extra_hwdef.close()
|
||||||
|
|
|
@ -0,0 +1,5 @@
|
||||||
|
rc 1 1500
|
||||||
|
rc 2 1500
|
||||||
|
rc 3 1000
|
||||||
|
rc 4 1500
|
||||||
|
rc 5 2000
|
Loading…
Reference in New Issue