mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: improve testing instructions for simulated rangefinders
This commit is contained in:
parent
fdb9fb2f62
commit
7b046c8b75
@ -19,7 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 23
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,8 +19,13 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 19
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,8 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 27
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,8 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 20
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -13,13 +13,18 @@
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
Simulator for the Lanbao rangefinder
|
||||
Simulator for the Lanbao rangefinder
|
||||
|
||||
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lanbao --speedup=1
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 26
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -15,11 +15,16 @@
|
||||
/*
|
||||
Simulator for the LeddarOne rangefinder
|
||||
|
||||
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:leddarone --speedup=1
|
||||
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:leddarone --speedup=1
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 12
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -13,13 +13,18 @@
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
Simulator for the serial LightWare rangefinder
|
||||
Simulator for the serial LightWare rangefinder
|
||||
|
||||
./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lightwareserial --speedup=1
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 8
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,7 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 13
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,7 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 17
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,7 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 18
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,7 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 11
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -19,7 +19,12 @@
|
||||
|
||||
param set SERIAL5_PROTOCOL 9
|
||||
param set RNGFND1_TYPE 11
|
||||
graph RANGEFINDER.distance
|
||||
graph GLOBAL_POSITION_INT.relative_alt/1000-RANGEFINDER.distance
|
||||
reboot
|
||||
|
||||
arm throttle
|
||||
rc 3 1600
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
Loading…
Reference in New Issue
Block a user