mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: adjust description of aux function 90 (EK3 Source Set
This commit is contained in:
parent
6d8f0decac
commit
12d8a4d543
@ -2,7 +2,7 @@
|
|||||||
-- this script is intended to help vehicles automatically switch between ExternalNav and optical flow
|
-- this script is intended to help vehicles automatically switch between ExternalNav and optical flow
|
||||||
--
|
--
|
||||||
-- configure a downward facing lidar with a range of at least 5m
|
-- configure a downward facing lidar with a range of at least 5m
|
||||||
-- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=external nav, middle=opticalflow, high=Not Used)
|
-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=external nav, middle=opticalflow, high=Not Used)
|
||||||
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
||||||
-- SRC_ENABLE = 1 (enable scripting)
|
-- SRC_ENABLE = 1 (enable scripting)
|
||||||
-- setup EK3_SRCn_ parameters so that ExternalNav is the primary source, opticalflow is secondary
|
-- setup EK3_SRCn_ parameters so that ExternalNav is the primary source, opticalflow is secondary
|
||||||
@ -135,7 +135,7 @@ end
|
|||||||
function update()
|
function update()
|
||||||
|
|
||||||
-- check for EKF Source Select switch position change
|
-- check for EKF Source Select switch position change
|
||||||
local rc_ekfsrc_pos = rc:get_aux_cached(90) -- RCx_OPTION = 90 (EKF Pos Source)
|
local rc_ekfsrc_pos = rc:get_aux_cached(90) -- RCx_OPTION = 90 (EKF Source Set)
|
||||||
if rc_ekfsrc_pos == nil then
|
if rc_ekfsrc_pos == nil then
|
||||||
rc_ekfsrc_pos = 0
|
rc_ekfsrc_pos = 0
|
||||||
end
|
end
|
||||||
|
@ -14,7 +14,7 @@ This script is intended to help vehicles automatically switch between ExternalNa
|
|||||||
## How to use
|
## How to use
|
||||||
|
|
||||||
Configure a downward facing lidar with a range of at least 5m
|
Configure a downward facing lidar with a range of at least 5m
|
||||||
Set RCx_OPTION = 90 (EKF Pos Source) to select the source (low=ExternalNav, middle=opticalflow, high=Not Used)
|
Set RCx_OPTION = 90 (EKF Source Set) to select the source (low=ExternalNav, middle=opticalflow, high=Not Used)
|
||||||
Set RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
Set RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
||||||
Set SRC_ENABLE = 1 (enable scripting)
|
Set SRC_ENABLE = 1 (enable scripting)
|
||||||
Set EK3_SRCn_ parameters so that ExternalNav is the primary source, opticalflow is secondary
|
Set EK3_SRCn_ parameters so that ExternalNav is the primary source, opticalflow is secondary
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
-- this script is intended to help vehicles automatically switch between GPS and optical flow
|
-- this script is intended to help vehicles automatically switch between GPS and optical flow
|
||||||
--
|
--
|
||||||
-- configure a forward or downward facing lidar with a range of at least 5m
|
-- configure a forward or downward facing lidar with a range of at least 5m
|
||||||
-- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=GPS, middle=opticalflow, high=Not Used)
|
-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=GPS, middle=opticalflow, high=Not Used)
|
||||||
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
||||||
-- SCR_ENABLE = 1 (enable scripting)
|
-- SCR_ENABLE = 1 (enable scripting)
|
||||||
-- setup EK3_SRCn_ parameters so that GPS is the primary source, opticalflow is secondary.
|
-- setup EK3_SRCn_ parameters so that GPS is the primary source, opticalflow is secondary.
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
-- This script helps vehicles move between GPS and Non-GPS environments using GPS and Wheel Encoders
|
-- This script helps vehicles move between GPS and Non-GPS environments using GPS and Wheel Encoders
|
||||||
--
|
--
|
||||||
-- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=primary, middle=secondary, high=tertiary)
|
-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=primary, middle=secondary, high=tertiary)
|
||||||
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
||||||
-- setup EK3_SRCn_ parameters so that GPS is the primary source, WheelEncoders are the secondary
|
-- setup EK3_SRCn_ parameters so that GPS is the primary source, WheelEncoders are the secondary
|
||||||
--
|
--
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
-- switches between AHRS/EKF sources based on the pilot's source selection switch or using an automatic source selection algorithm
|
-- switches between AHRS/EKF sources based on the pilot's source selection switch or using an automatic source selection algorithm
|
||||||
-- this script is intended to help vehicles move between GPS and Non-GPS environments
|
-- this script is intended to help vehicles move between GPS and Non-GPS environments
|
||||||
--
|
--
|
||||||
-- setup RCx_OPTION = 90 (EKF Pos Source) to select the source (low=primary, middle=secondary, high=tertiary)
|
-- setup RCx_OPTION = 90 (EKF Source Set) to select the source (low=primary, middle=secondary, high=tertiary)
|
||||||
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
-- setup RCx_OPTION = 300 (Scripting1). When this switch is pulled high, the source will be automatically selected
|
||||||
-- setup EK3_SRCn_ parameters so that GPS is the primary source, Non-GPS (i.e. T265) is secondary and optical flow tertiary
|
-- setup EK3_SRCn_ parameters so that GPS is the primary source, Non-GPS (i.e. T265) is secondary and optical flow tertiary
|
||||||
-- configure a forward or downward facing lidar with a range of more than 5m
|
-- configure a forward or downward facing lidar with a range of more than 5m
|
||||||
|
Loading…
Reference in New Issue
Block a user