mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: rename GPS_ to GPS1_
This commit is contained in:
parent
0256cef7b9
commit
bb83c43d1b
@ -39,10 +39,10 @@
|
|||||||
-- Test on a real vehicle:
|
-- Test on a real vehicle:
|
||||||
-- A. set DR_FLY_TIMEOUT to a low value (e.g. 5 seconds)
|
-- A. set DR_FLY_TIMEOUT to a low value (e.g. 5 seconds)
|
||||||
-- B. fly the vehicle at least DR_DIST_MIN meters from home and confirm the "DR: activated!" message is displayed
|
-- B. fly the vehicle at least DR_DIST_MIN meters from home and confirm the "DR: activated!" message is displayed
|
||||||
-- C. set GPS_TYPE = 0 to disable GPS and confirm the vehicle begins deadreckoning after a few seconds
|
-- C. set GPS1_TYPE = 0 to disable GPS and confirm the vehicle begins deadreckoning after a few seconds
|
||||||
-- D. restore GPS_TYPE to its original value (normally 1) and confirm the vehicle switches to DR_NEXT_MODE
|
-- D. restore GPS1_TYPE to its original value (normally 1) and confirm the vehicle switches to DR_NEXT_MODE
|
||||||
-- E. restore DR_FLY_TIMEOUT to a higher value for real-world use
|
-- E. restore DR_FLY_TIMEOUT to a higher value for real-world use
|
||||||
-- Note: Instaed of setting GPS_TYPE, an auxiliary function switch can be setup to disable the GPS (e.g. RC9_OPTION = 65/"Disable GPS")
|
-- Note: Instaed of setting GPS1_TYPE, an auxiliary function switch can be setup to disable the GPS (e.g. RC9_OPTION = 65/"Disable GPS")
|
||||||
--
|
--
|
||||||
-- Testing that it does not require RC (in SITL):
|
-- Testing that it does not require RC (in SITL):
|
||||||
-- a. set FS_OPTIONS's "Continue if in Guided on RC failsafe" bit
|
-- a. set FS_OPTIONS's "Continue if in Guided on RC failsafe" bit
|
||||||
|
@ -48,11 +48,11 @@ Deadreckoning will only be activated while the vehicle is in autonomous modes (e
|
|||||||
|
|
||||||
1. set DR_FLY_TIMEOUT to a low value (e.g. 5 seconds)
|
1. set DR_FLY_TIMEOUT to a low value (e.g. 5 seconds)
|
||||||
2. fly the vehicle at least DR_DIST_MIN meters from home and confirm the "DR: activated!" message is displayed
|
2. fly the vehicle at least DR_DIST_MIN meters from home and confirm the "DR: activated!" message is displayed
|
||||||
3. set GPS_TYPE = 0 to disable GPS and confirm the vehicle begins deadreckoning after a few seconds
|
3. set GPS1_TYPE = 0 to disable GPS and confirm the vehicle begins deadreckoning after a few seconds
|
||||||
4. restore GPS_TYPE to its original value (normally 1) and confirm the vehicle switches to DR_NEXT_MODE
|
4. restore GPS1_TYPE to its original value (normally 1) and confirm the vehicle switches to DR_NEXT_MODE
|
||||||
5. restore DR_FLY_TIMEOUT to a higher value for real-world use
|
5. restore DR_FLY_TIMEOUT to a higher value for real-world use
|
||||||
|
|
||||||
Note: Instaed of setting GPS_TYPE, an auxiliary function switch can be setup to disable the GPS (e.g. RC9_OPTION = 65/"Disable GPS")
|
Note: Instaed of setting GPS1_TYPE, an auxiliary function switch can be setup to disable the GPS (e.g. RC9_OPTION = 65/"Disable GPS")
|
||||||
|
|
||||||
## Testing that it does not require RC (in SITL):
|
## Testing that it does not require RC (in SITL):
|
||||||
- set FS_OPTIONS's "Continue if in Guided on RC failsafe" bit
|
- set FS_OPTIONS's "Continue if in Guided on RC failsafe" bit
|
||||||
|
Loading…
Reference in New Issue
Block a user