60002_uuv_bluerov2_heavy
1.39 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
#!/bin/sh
#
# @name BlueROV2 (Heavy Configuration)
#
# @type Vectored 6 DOF UUV
# @class Underwater Robot
#
# @output MAIN1 motor 1 CCW, bow starboard horizontal, , propeller CCW
# @output MAIN2 motor 2 CCW, bow port horizontal, propeller CCW
# @output MAIN3 motor 3 CCW, stern starboard horizontal, propeller CW
# @output MAIN4 motor 4 CCW, stern port horizontal, propeller CW
# @output MAIN5 motor 5 CCW, bow starboard vertical, propeller CCW
# @output MAIN6 motor 6 CCW, bow port vertical, propeller CW
# @output MAIN7 motor 7 CCW, stern starboard vertical, propeller CW
# @output MAIN8 motor 8 CCW, stern port vertical, propeller CCW
#
# @maintainer Thies Lennart Alff <thies.lennart.alff@tuhh.de>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.uuv_defaults
#Set data link loss failsafe mode (0: disabled)
param set-default NAV_DLL_ACT 0
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
# companion computer is connected via USB permanently
param set-default CBRK_USB_CHK 197848
param set-default CBRK_IO_SAFETY 22027
param set-default COM_PREARM_MODE 0
param set-default MAV_1_CONFIG 102
param set-default BAT1_A_PER_V 37.8798
param set-default BAT1_CAPACITY 18000
param set-default BAT1_V_DIV 11.0
param set-default BAT1_N_CELLS 4
param set-default BAT_V_OFFS_CURR 0.33
set PWM_OUT 12345678
# set MIXER IO_pass
set MIXER vectored6dof