SITL: add on-hardware example files

This commit is contained in:
Peter Barker 2022-03-08 09:46:31 +11:00 committed by Peter Barker
parent fa2e841387
commit ebe2205ba7
5 changed files with 193 additions and 0 deletions

View File

@ -0,0 +1,66 @@
# 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.sh
## 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

View File

@ -0,0 +1,59 @@
AHRS_EKF_TYPE 10
ATC_RAT_YAW_P 0.09
ATC_RAT_YAW_I 0.009
BATT_MONITOR 0
COMPASS_OFS_X 5
COMPASS_OFS_Y 13
COMPASS_OFS_Z -18
COMPASS_OFS2_X 5
COMPASS_OFS2_Y 13
COMPASS_OFS2_Z -18
FENCE_RADIUS 150
FRAME_TYPE 0
FRAME_CLASS 1
FS_THR_ENABLE 1
RC7_OPTION 7
FLTMODE1 7
FLTMODE2 9
FLTMODE3 6
FLTMODE4 3
FLTMODE5 5
FLTMODE6 0
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
MOT_THST_EXPO 0.65
MOT_THST_HOVER 0.39
MOT_BAT_VOLT_MIN 9.6
MOT_BAT_VOLT_MAX 12.8
SCHED_DEBUG 0
SIM_MAG1_DEVID 97539
SIM_BARO_RND 0
SIM_RATE_HZ 400
SCHED_LOOP_RATE 400
BRD_RTC_TYPES 2

View File

@ -0,0 +1,46 @@
env SIM_ENABLED 1
define INS_MAX_INSTANCES 2
define HAL_COMPASS_MAX_SENSORS 2
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_MOUNT_ENABLED 0
define HAL_PROXIMITY_ENABLED 0
define HAL_VISUALODOM_ENABLED 0
define HAL_GENERATOR_ENABLED 0
# define HAL_LOGGING_ENABLED 0
define HAL_CRSF_TELEM_ENABLED 0
#define OSD_ENABLED 0
define FRAME_HEXA 0
define FRAME_OCTA 0
define FRAME_DODECAHEXA 0
define FRAME_Y6 0
define FRAME_OCTAQUAD 0
define MODE_SMARTRTL_ENABLED 0
define MODE_SPORT_ENABLED 0
# define MODE_CIRCLE_ENABLED 0
define MODE_THROW_ENABLED 0
define MODE_TURTLE_ENABLED 0
define MODE_ZIGZAG_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 LANDING_GEAR_ENABLED 0
define HAL_MSP_OPTICALFLOW_ENABLED 0
define HAL_SUPPORT_RCOUT_SERIAL 0
define HAL_HOTT_TELEM_ENABLED 0
# define HAL_WITH_DSP 0
define HAL_HIGH_LATENCY2 0

View File

@ -0,0 +1,17 @@
#!/bin/bash
set -e
set -x
BOARD=NucleoH743
BOARD=MatekH743
#BOARD=F35Lightning
THISDIR=$(dirname $0)
./waf configure \
--board=$BOARD \
--extra-hwdef="$THISDIR/extra-hwdef-sitl-on-hw.dat" \
--default-param="$THISDIR/default.param"
./waf copter --upload

View File

@ -0,0 +1,5 @@
rc 1 1500
rc 2 1500
rc 3 1000
rc 4 1500
rc 5 2000