Michael Oborne
4 years ago
committed by
Andrew Tridgell
5 changed files with 140 additions and 0 deletions
Binary file not shown.
@ -0,0 +1,49 @@
@@ -0,0 +1,49 @@
|
||||
BATT_AMP_PERVLT 39.877 |
||||
BATT_VOLT_MULT 12.02 |
||||
AHRS_EKF_TYPE 2 @READONLY |
||||
AHRS_ORIENTATION 2 @READONLY |
||||
ATC_ACCEL_P_MAX 160000 @READONLY |
||||
ATC_ACCEL_R_MAX 392244 @READONLY |
||||
ATC_ACCEL_Y_MAX 35000 @READONLY |
||||
ATC_ANG_RLL_P 15.876 @READONLY |
||||
ATC_RAT_PIT_D 0.004 @READONLY |
||||
ATC_RAT_PIT_I 0.098 @READONLY |
||||
ATC_RAT_PIT_P 0.18 @READONLY |
||||
ATC_RAT_RLL_D 0.00113 @READONLY |
||||
ATC_RAT_RLL_I 0.0401 @READONLY |
||||
ATC_RAT_RLL_P 0.0401 @READONLY |
||||
BATT_MONITOR 4 |
||||
BATT_FS_LOW_ACT 1 @READONLY |
||||
BATT_LOW_VOLT 11 |
||||
BRD_SAFETYENABLE 0 |
||||
CAN_P1_DRIVER 1 |
||||
CAN_P2_DRIVER 1 |
||||
FENCE_ALT_MAX 15 @READONLY |
||||
FENCE_ENABLE 1 |
||||
FENCE_RADIUS 100 @READONLY |
||||
FLTMODE_CH 6 @READONLY |
||||
FLTMODE1 2 @READONLY |
||||
FLTMODE2 2 @READONLY |
||||
FLTMODE3 2 @READONLY |
||||
FLTMODE4 2 @READONLY |
||||
FLTMODE5 9 @READONLY |
||||
FLTMODE6 9 @READONLY |
||||
FRAME_CLASS 1 @READONLY |
||||
FS_OPTIONS 0 @READONLY |
||||
FS_THR_ENABLE 3 @READONLY |
||||
FS_THR_VALUE 950 @READONLY |
||||
GPS_TYPE 9 @READONLY |
||||
INS_GYRO_FILTER 100 |
||||
MOT_THST_HOVER 0.4028862 |
||||
NTF_LED_TYPES 231 @READONLY |
||||
RC_OPTIONS 0 |
||||
RC5_OPTION 41 |
||||
RC8_MIN 1000 |
||||
RC8_OPTION 17 |
||||
SERIAL1_PROTOCOL 2 |
||||
WPNAV_ACCEL 100 @READONLY |
||||
WPNAV_SPEED 500 @READONLY |
||||
SCR_ENABLE 1 @READONLY |
||||
SCR_DIR_DISABLE 0 @READONLY |
||||
BRD_IMUHEAT_I 0.07 @READONLY |
||||
BRD_IMUHEAT_P 50 @READONLY |
@ -0,0 +1,16 @@
@@ -0,0 +1,16 @@
|
||||
# hw definition file for processing by chibios_hwdef.py |
||||
# for H743 bootloader |
||||
|
||||
include ../CubeOrange/hwdef-bl.dat |
||||
|
||||
undef USB_STRING_PRODUCT |
||||
undef USB_STRING_MANUFACTURER |
||||
undef APJ_BOARD_ID |
||||
undef USB_PRODUCT |
||||
|
||||
# USB setup |
||||
USB_PRODUCT 0x1056 |
||||
USB_STRING_MANUFACTURER "CubePilot" |
||||
USB_STRING_PRODUCT "Joey-BL" |
||||
|
||||
APJ_BOARD_ID 1033 |
@ -0,0 +1,15 @@
@@ -0,0 +1,15 @@
|
||||
# hw definition file for processing by chibios_hwdef.py |
||||
|
||||
include ../CubeOrange/hwdef.dat |
||||
|
||||
undef USB_STRING_PRODUCT |
||||
undef USB_STRING_MANUFACTURER |
||||
undef APJ_BOARD_ID |
||||
undef USB_PRODUCT |
||||
|
||||
# USB setup |
||||
USB_PRODUCT 0x1057 |
||||
USB_STRING_MANUFACTURER "CubePilot" |
||||
USB_STRING_PRODUCT "Joey" |
||||
|
||||
APJ_BOARD_ID 1033 |
@ -0,0 +1,60 @@
@@ -0,0 +1,60 @@
|
||||
|
||||
-- 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate |
||||
-- and arming:is_armed() |
||||
|
||||
local MODE_AUTO = 3 |
||||
local MODE_LOITER = 5 |
||||
local MODE_ALT_HOLD = 2 |
||||
local MODE_RTL = 6 |
||||
local MODE_LAND = 9 |
||||
local counter = 0 |
||||
|
||||
function update() |
||||
local pos = ahrs:get_position() |
||||
|
||||
if (vehicle:get_mode() == MODE_AUTO or vehicle:get_mode() == MODE_LOITER) then |
||||
setfence(true) |
||||
elseif vehicle:get_mode() == MODE_ALT_HOLD and not pos then |
||||
setfence(false) |
||||
elseif vehicle:get_mode() == MODE_ALT_HOLD and pos then |
||||
setfence(true) |
||||
end |
||||
|
||||
if (vehicle:get_mode() ~= MODE_AUTO and vehicle:get_mode() ~= MODE_LOITER and vehicle:get_mode() ~= MODE_ALT_HOLD and vehicle:get_mode() ~= MODE_RTL and vehicle:get_mode() ~= MODE_LAND) then |
||||
if not pos then |
||||
vehicle:set_mode(MODE_ALT_HOLD) |
||||
gcs:send_text(0, "JoeyFence: Invalid Mode, Changing no gps") |
||||
else |
||||
vehicle:set_mode(MODE_LOITER) |
||||
gcs:send_text(0, "JoeyFence: Invalid Mode, Changing gps") |
||||
end |
||||
end |
||||
|
||||
if (counter >= 5 * 5) then |
||||
--gcs:send_text(0, "JoeyFence: Running") |
||||
counter = 0 |
||||
end |
||||
|
||||
counter = counter + 1 |
||||
-- run at 5Hz |
||||
return update, 200 |
||||
end |
||||
|
||||
function setfence(enabled) |
||||
if (enabled) then |
||||
value = param:get('FENCE_ENABLE') |
||||
if(value ~= 1) then |
||||
param:set('FENCE_ENABLE',1) |
||||
gcs:send_text(0, "JoeyFence: Enabled") |
||||
end |
||||
else |
||||
value = param:get('FENCE_ENABLE') |
||||
if(value ~= 0) then |
||||
param:set('FENCE_ENABLE',0) |
||||
gcs:send_text(0, "JoeyFence: Disabled") |
||||
end |
||||
end |
||||
end |
||||
|
||||
-- start running update loop |
||||
return update() |
Loading…
Reference in new issue