airframes: added BlueROV2 (heavy configuration) airframe (#16004)

This commit is contained in:
Thies Lennart Alff
2020-10-28 11:07:31 +01:00
committed by GitHub
parent 5b7d1a0496
commit 82988b1912
12 changed files with 155 additions and 2 deletions
@@ -0,0 +1,20 @@
#!/bin/sh
#
# @name BlueROV2 Heavy Configuration
#
. ${R}etc/init.d/rc.uuv_defaults
if [ $AUTOCNF = yes ]
then
#Set data link loss failsafe mode (0: disabled)
param set NAV_DLL_ACT 0
# disable circuit breaker for airspeed sensor
param set CBRK_AIRSPD_CHK 162128
fi
set PWM_OUT 12345678
set MIXER_FILE etc/mixers-sitl/vectored6dof_sitl.main.mix
set MIXER custom
@@ -51,6 +51,7 @@ px4_add_romfs_files(
1019_iris_dual_gps
1020_uuv_generic
1021_uuv_hippocampus
1022_uuv_bluerov2_heavy
1030_plane
1031_plane_cam
1032_plane_catapult
@@ -0,0 +1,51 @@
#!/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 intel_aerofc-v1 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.uuv_defaults
if [ $AUTOCNF = yes ]
then
#Set data link loss failsafe mode (0: disabled)
param set NAV_DLL_ACT 0
# disable circuit breaker for airspeed sensor
param set CBRK_AIRSPD_CHK 162128
# companion computer is connected via USB permanently
param set CBRK_USB_CHK 197848
param set CBRK_IO_SAFETY 22027
param set COM_PREARM_MODE 0
param set MAV_1_CONFIG 102
param set BAT1_A_PER_V 37.8798
param set BAT1_CAPACITY 18000
param set BAT1_V_DIV 11.0
param set BAT1_N_CELLS 4
param set BAT_V_OFFS_CURR 0.33
fi
set PWM_OUT 12345678
# set MIXER IO_pass
set MIXER vectored6dof
@@ -158,4 +158,5 @@ px4_add_romfs_files(
# [60000, 61000] (Unmanned) Underwater Robots
60000_uuv_generic
60001_uuv_hippocampus
60002_uuv_bluerov2_heavy
)
@@ -183,6 +183,13 @@ then
echo "UUV mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set default MAV_TYPE to submarine if not defined
set MAV_TYPE 12
fi
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@@ -42,4 +42,5 @@ px4_add_romfs_files(
standard_vtol_sitl.main.mix
tiltrotor_sitl.main.mix
uuv_x_sitl.main.mix
vectored6dof_sitl.main.mix
)
@@ -0,0 +1,32 @@
# Motor 1
M: 2
S: 0 2 -4000 -4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 2
M: 2
S: 0 2 +4000 +4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 3
M: 2
S: 0 2 -4000 -4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 4
M: 2
S: 0 2 +4000 +4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 5
M: 2
S: 0 0 -4000 -4000 0 -4000 +4000
S: 0 1 +4000 +4000 0 -4000 +4000
# Motor 6
M: 2
S: 0 0 -4000 -4000 0 -4000 +4000
S: 0 1 -4000 -4000 0 -4000 +4000
# Motor 7
M: 2
S: 0 0 +4000 +4000 0 -4000 +4000
S: 0 1 +4000 +4000 0 -4000 +4000
# Motor 8
M: 2
S: 0 0 +4000 +4000 0 -4000 +4000
S: 0 1 -4000 -4000 0 -4000 +4000
@@ -85,6 +85,7 @@ px4_add_romfs_files(
tri_y_yaw+.main.mix
tri_y_yaw-.main.mix
uuv_x.main.mix
vectored6dof.main.mix
Viper.main.mix
vtol_AAERT.aux.mix
vtol_AAVVT.aux.mix
@@ -0,0 +1,32 @@
# Motor 1
M: 2
S: 0 2 -4000 -4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 2
M: 2
S: 0 2 +4000 +4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 3
M: 2
S: 0 2 -4000 -4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 4
M: 2
S: 0 2 +4000 +4000 0 -4000 +4000
S: 0 3 +4000 +4000 0 -4000 +4000
# Motor 5
M: 2
S: 0 0 -4000 -4000 0 -4000 +4000
S: 0 1 +4000 +4000 0 -4000 +4000
# Motor 6
M: 2
S: 0 0 -4000 -4000 0 -4000 +4000
S: 0 1 -4000 -4000 0 -4000 +4000
# Motor 7
M: 2
S: 0 0 +4000 +4000 0 -4000 +4000
S: 0 1 +4000 +4000 0 -4000 +4000
# Motor 8
M: 2
S: 0 0 +4000 +4000 0 -4000 +4000
S: 0 1 -4000 -4000 0 -4000 +4000
+1
View File
@@ -90,6 +90,7 @@ px4_add_board(
sensors
sih
temperature_compensation
uuv_att_control
vmount
vtol_att_control
SYSTEMCMDS
+1 -1
View File
@@ -96,7 +96,7 @@ set(models none shell
plane plane_cam plane_catapult plane_lidar techpod
standard_vtol tailsitter tiltrotor
rover r1_rover boat cloudship
uuv_hippocampus)
uuv_hippocampus uuv_bluerov2_heavy)
set(worlds none empty baylands ksql_airport mcmillan_airfield sonoma_raceway warehouse windy)
set(all_posix_vmd_make_targets)
foreach(viewer ${viewers})
+7 -1
View File
@@ -96,14 +96,20 @@ mavlink_hil_actuator_controls_t Simulator::actuator_controls_from_outputs()
_system_type == MAV_TYPE_VTOL_DUOROTOR ||
_system_type == MAV_TYPE_VTOL_QUADROTOR ||
_system_type == MAV_TYPE_VTOL_TILTROTOR ||
_system_type == MAV_TYPE_VTOL_RESERVED2) {
_system_type == MAV_TYPE_VTOL_RESERVED2 ||
_system_type == MAV_TYPE_SUBMARINE) {
/* multirotors: set number of rotor outputs depending on type */
unsigned n;
switch (_system_type) {
case MAV_TYPE_SUBMARINE:
n = 0;
break;
case MAV_TYPE_AIRSHIP:
case MAV_TYPE_VTOL_DUOROTOR:
n = 2;
break;