Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
2ed50262
Commit
2ed50262
authored
Aug 02, 2016
by
Don Gagne
Committed by
GitHub
Aug 02, 2016
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #3897 from bluerobotics/ardusubMocklink
Add mock link for ArduSub Firmware Plugin testing
parents
6039eb9a
2d54faaa
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
635 additions
and
0 deletions
+635
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
QGroundControlQmlGlobal.cc
src/QmlControls/QGroundControlQmlGlobal.cc
+9
-0
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+1
-0
APMArduSubMockLink.params
src/comm/APMArduSubMockLink.params
+605
-0
MockLink.cc
src/comm/MockLink.cc
+14
-0
MockLink.h
src/comm/MockLink.h
+1
-0
MockLink.qml
src/ui/preferences/MockLink.qml
+4
-0
No files found.
qgroundcontrol.qrc
View file @
2ed50262
...
...
@@ -3,6 +3,7 @@
<file alias="PX4MockLink.params">src/comm/PX4MockLink.params</file>
<file alias="APMArduCopterMockLink.params">src/comm/APMArduCopterMockLink.params</file>
<file alias="APMArduPlaneMockLink.params">src/comm/APMArduPlaneMockLink.params</file>
<file alias="APMArduSubMockLink.params">src/comm/APMArduSubMockLink.params</file>
<file alias="FactSystemTest.qml">src/FactSystem/FactSystemTest.qml</file>
</qresource>
<qresource prefix="/qml">
...
...
src/QmlControls/QGroundControlQmlGlobal.cc
View file @
2ed50262
...
...
@@ -137,6 +137,15 @@ void QGroundControlQmlGlobal::startAPMArduPlaneMockLink(bool sendStatusText)
#endif
}
void
QGroundControlQmlGlobal
::
startAPMArduSubMockLink
(
bool
sendStatusText
)
{
#ifdef QT_DEBUG
MockLink
::
startAPMArduSubMockLink
(
sendStatusText
);
#else
Q_UNUSED
(
sendStatusText
);
#endif
}
void
QGroundControlQmlGlobal
::
stopAllMockLinks
(
void
)
{
#ifdef QT_DEBUG
...
...
src/QmlControls/QGroundControlQmlGlobal.h
View file @
2ed50262
...
...
@@ -123,6 +123,7 @@ public:
Q_INVOKABLE
void
startGenericMockLink
(
bool
sendStatusText
);
Q_INVOKABLE
void
startAPMArduCopterMockLink
(
bool
sendStatusText
);
Q_INVOKABLE
void
startAPMArduPlaneMockLink
(
bool
sendStatusText
);
Q_INVOKABLE
void
startAPMArduSubMockLink
(
bool
sendStatusText
);
Q_INVOKABLE
void
stopAllMockLinks
(
void
);
/// Converts from meters to the user specified distance unit
...
...
src/comm/APMArduSubMockLink.params
0 → 100755
View file @
2ed50262
# Onboard parameters for vehicle 128
#
# MAV ID COMPONENT ID PARAM NAME VALUE (FLOAT)
128 1 ACCEL_Z_D 0.000000000000000000 9
128 1 ACCEL_Z_FILT 20.000000000000000000 9
128 1 ACCEL_Z_I 1.000000000000000000 9
128 1 ACCEL_Z_IMAX 800.000000000000000000 9
128 1 ACCEL_Z_P 0.500000000000000000 9
128 1 ACRO_BAL_PITCH 1.000000000000000000 9
128 1 ACRO_BAL_ROLL 1.000000000000000000 9
128 1 ACRO_EXPO 0.300000011920928955 9
128 1 ACRO_RP_P 4.500000000000000000 9
128 1 ACRO_TRAINER 2 2
128 1 ACRO_YAW_P 4.500000000000000000 9
128 1 AHRS_COMP_BETA 0.100000001490116119 9
128 1 AHRS_EKF_TYPE 2 2
128 1 AHRS_GPS_GAIN 1.000000000000000000 9
128 1 AHRS_GPS_MINSATS 6 2
128 1 AHRS_GPS_USE 1 2
128 1 AHRS_ORIENTATION 16 2
128 1 AHRS_RP_P 0.200000002980232239 9
128 1 AHRS_TRIM_X -0.017862198874354362 9
128 1 AHRS_TRIM_Y -0.001083165174350142 9
128 1 AHRS_TRIM_Z 0.000000000000000000 9
128 1 AHRS_WIND_MAX 0 2
128 1 AHRS_YAW_P 0.200000002980232239 9
128 1 ANGLE_MAX 4500 4
128 1 ARMING_CHECK 0 2
128 1 ATC_ACCEL_P_MAX 110000.000000000000000000 9
128 1 ATC_ACCEL_R_MAX 110000.000000000000000000 9
128 1 ATC_ACCEL_Y_MAX 0.000000000000000000 9
128 1 ATC_ANGLE_BOOST 1 2
128 1 ATC_ANG_LIM_TC 1.000000000000000000 9
128 1 ATC_ANG_PIT_P 6.000000000000000000 9
128 1 ATC_ANG_RLL_P 6.000000000000000000 9
128 1 ATC_ANG_YAW_P 6.000000000000000000 9
128 1 ATC_RATE_FF_ENAB 1 2
128 1 ATC_RAT_PIT_D 0.003599999938160181 9
128 1 ATC_RAT_PIT_FILT 20.000000000000000000 9
128 1 ATC_RAT_PIT_I 0.090000003576278687 9
128 1 ATC_RAT_PIT_IMAX 0.444000005722045898 9
128 1 ATC_RAT_PIT_P 0.135000005364418030 9
128 1 ATC_RAT_RLL_D 0.000000000000000000 9
128 1 ATC_RAT_RLL_FILT 20.000000000000000000 9
128 1 ATC_RAT_RLL_I 0.000000000000000000 9
128 1 ATC_RAT_RLL_IMAX 0.444000005722045898 9
128 1 ATC_RAT_RLL_P 0.000000000000000000 9
128 1 ATC_RAT_YAW_D 0.000000000000000000 9
128 1 ATC_RAT_YAW_FILT 30.000000000000000000 9
128 1 ATC_RAT_YAW_I 0.019999999552965164 9
128 1 ATC_RAT_YAW_IMAX 0.222000002861022949 9
128 1 ATC_RAT_YAW_P 0.180000007152557373 9
128 1 ATC_SLEW_YAW 6000.000000000000000000 9
128 1 ATC_THR_MIX_MAX 0.500000000000000000 9
128 1 ATC_THR_MIX_MIN 0.100000001490116119 9
128 1 AUTOTUNE_AGGR 0.100000001490116119 9
128 1 AUTOTUNE_AXES 7 2
128 1 AUTOTUNE_MIN_D 0.001000000047497451 9
128 1 AVOID_ENABLE 1 2
128 1 BATT2_AMP_OFFSET 0.000000000000000000 9
128 1 BATT2_AMP_PERVOL 17.000000000000000000 9
128 1 BATT2_CAPACITY 3300 6
128 1 BATT2_CURR_PIN 3 2
128 1 BATT2_MONITOR 0 2
128 1 BATT2_VOLT_MULT 10.100000381469726562 9
128 1 BATT2_VOLT_PIN 2 2
128 1 BATT_AMP_OFFSET 0.000000000000000000 9
128 1 BATT_AMP_PERVOLT 17.000000000000000000 9
128 1 BATT_CAPACITY 18000 6
128 1 BATT_CURR_PIN 3 2
128 1 BATT_MONITOR 4 2
128 1 BATT_VOLT_MULT 10.100000381469726562 9
128 1 BATT_VOLT_PIN 2 2
128 1 BRD_CAN_ENABLE 0 2
128 1 BRD_IMU_TARGTEMP 0 2
128 1 BRD_PWM_COUNT 4 2
128 1 BRD_SAFETYENABLE 0 2
128 1 BRD_SAFETY_MASK 0 6
128 1 BRD_SBUS_OUT 0 2
128 1 BRD_SER1_RTSCTS 2 2
128 1 BRD_SER2_RTSCTS 2 2
128 1 BRD_SERIAL_NUM 0 4
128 1 BTN0_FUNCTION 0 2
128 1 BTN0_SFUNCTION 0 2
128 1 BTN10_FUNCTION 48 2
128 1 BTN10_SFUNCTION 0 2
128 1 BTN11_FUNCTION 42 2
128 1 BTN11_SFUNCTION 0 2
128 1 BTN12_FUNCTION 43 2
128 1 BTN12_SFUNCTION 0 2
128 1 BTN13_FUNCTION 33 2
128 1 BTN13_SFUNCTION 45 2
128 1 BTN14_FUNCTION 32 2
128 1 BTN14_SFUNCTION 44 2
128 1 BTN15_FUNCTION 0 2
128 1 BTN15_SFUNCTION 0 2
128 1 BTN1_FUNCTION 6 2
128 1 BTN1_SFUNCTION 0 2
128 1 BTN2_FUNCTION 8 2
128 1 BTN2_SFUNCTION 0 2
128 1 BTN3_FUNCTION 7 2
128 1 BTN3_SFUNCTION 0 2
128 1 BTN4_FUNCTION 22 2
128 1 BTN4_SFUNCTION 0 2
128 1 BTN5_FUNCTION 23 2
128 1 BTN5_SFUNCTION 0 2
128 1 BTN6_FUNCTION 4 2
128 1 BTN6_SFUNCTION 0 2
128 1 BTN7_FUNCTION 3 2
128 1 BTN7_SFUNCTION 0 2
128 1 BTN8_FUNCTION 1 2
128 1 BTN8_SFUNCTION 0 2
128 1 BTN9_FUNCTION 21 2
128 1 BTN9_SFUNCTION 0 2
128 1 CAM_DURATION 10 2
128 1 CAM_FEEDBACK_PIN 0 2
128 1 CAM_FEEDBACK_POL 1 2
128 1 CAM_MAX_ROLL 0 4
128 1 CAM_MIN_INTERVAL 0 4
128 1 CAM_RELAY_ON 1 2
128 1 CAM_SERVO_OFF 1100 4
128 1 CAM_SERVO_ON 1300 4
128 1 CAM_TRIGG_DIST 0.000000000000000000 9
128 1 CAM_TRIGG_TYPE 0 2
128 1 CH10_OPT 0 2
128 1 CH11_OPT 0 2
128 1 CH12_OPT 0 2
128 1 CH7_OPT 0 2
128 1 CH8_OPT 0 2
128 1 CH9_OPT 0 2
128 1 CIRCLE_RADIUS 1000.000000000000000000 9
128 1 CIRCLE_RATE 20.000000000000000000 9
128 1 CLI_ENABLED 0 2
128 1 COMPASS_AUTODEC 1 2
128 1 COMPASS_CAL_FIT 8.000000000000000000 9
128 1 COMPASS_DEC 0.000000000000000000 9
128 1 COMPASS_DEV_ID 131594 6
128 1 COMPASS_DEV_ID2 0 6
128 1 COMPASS_DEV_ID3 0 6
128 1 COMPASS_DIA2_X 0.000000000000000000 9
128 1 COMPASS_DIA2_Y 0.000000000000000000 9
128 1 COMPASS_DIA2_Z 0.000000000000000000 9
128 1 COMPASS_DIA3_X 0.000000000000000000 9
128 1 COMPASS_DIA3_Y 0.000000000000000000 9
128 1 COMPASS_DIA3_Z 0.000000000000000000 9
128 1 COMPASS_DIA_X 1.000000000000000000 9
128 1 COMPASS_DIA_Y 1.000000000000000000 9
128 1 COMPASS_DIA_Z 1.000000000000000000 9
128 1 COMPASS_EXTERN2 0 2
128 1 COMPASS_EXTERN3 0 2
128 1 COMPASS_EXTERNAL 0 2
128 1 COMPASS_LEARN 1 2
128 1 COMPASS_MOT2_X 0.000000000000000000 9
128 1 COMPASS_MOT2_Y 0.000000000000000000 9
128 1 COMPASS_MOT2_Z 0.000000000000000000 9
128 1 COMPASS_MOT3_X 0.000000000000000000 9
128 1 COMPASS_MOT3_Y 0.000000000000000000 9
128 1 COMPASS_MOT3_Z 0.000000000000000000 9
128 1 COMPASS_MOTCT 0 2
128 1 COMPASS_MOT_X 0.000000000000000000 9
128 1 COMPASS_MOT_Y 0.000000000000000000 9
128 1 COMPASS_MOT_Z 0.000000000000000000 9
128 1 COMPASS_ODI2_X 0.000000000000000000 9
128 1 COMPASS_ODI2_Y 0.000000000000000000 9
128 1 COMPASS_ODI2_Z 0.000000000000000000 9
128 1 COMPASS_ODI3_X 0.000000000000000000 9
128 1 COMPASS_ODI3_Y 0.000000000000000000 9
128 1 COMPASS_ODI3_Z 0.000000000000000000 9
128 1 COMPASS_ODI_X 0.000000000000000000 9
128 1 COMPASS_ODI_Y 0.000000000000000000 9
128 1 COMPASS_ODI_Z 0.000000000000000000 9
128 1 COMPASS_OFS2_X 0.000000000000000000 9
128 1 COMPASS_OFS2_Y 0.000000000000000000 9
128 1 COMPASS_OFS2_Z 0.000000000000000000 9
128 1 COMPASS_OFS3_X 0.000000000000000000 9
128 1 COMPASS_OFS3_Y 0.000000000000000000 9
128 1 COMPASS_OFS3_Z 0.000000000000000000 9
128 1 COMPASS_OFS_X -68.000000000000000000 9
128 1 COMPASS_OFS_Y 166.000000000000000000 9
128 1 COMPASS_OFS_Z -435.000000000000000000 9
128 1 COMPASS_ORIENT 0 2
128 1 COMPASS_ORIENT2 0 2
128 1 COMPASS_ORIENT3 0 2
128 1 COMPASS_PRIMARY 0 2
128 1 COMPASS_USE 1 2
128 1 COMPASS_USE2 1 2
128 1 COMPASS_USE3 1 2
128 1 DISARM_DELAY 0 2
128 1 EK2_ABIAS_P_NSE 0.004999999888241291 9
128 1 EK2_ACC_P_NSE 0.600000023841857910 9
128 1 EK2_ALT_M_NSE 0.100000001490116119 9
128 1 EK2_ALT_SOURCE 0 2
128 1 EK2_CHECK_SCALE 100 4
128 1 EK2_EAS_I_GATE 400 4
128 1 EK2_EAS_M_NSE 1.399999976158142090 9
128 1 EK2_ENABLE 1 2
128 1 EK2_FLOW_DELAY 10 2
128 1 EK2_FLOW_I_GATE 300 4
128 1 EK2_FLOW_M_NSE 0.250000000000000000 9
128 1 EK2_GBIAS_P_NSE 0.000099999997473788 9
128 1 EK2_GLITCH_RAD 25 2
128 1 EK2_GPS_CHECK 31 2
128 1 EK2_GPS_DELAY 220 4
128 1 EK2_GPS_TYPE 0 2
128 1 EK2_GSCL_P_NSE 0.000500000023748726 9
128 1 EK2_GYRO_P_NSE 0.029999999329447746 9
128 1 EK2_HGT_DELAY 60 4
128 1 EK2_HGT_I_GATE 500 4
128 1 EK2_IMU_MASK 3 2
128 1 EK2_LOG_MASK 1 2
128 1 EK2_MAGB_P_NSE 0.000099999997473788 9
128 1 EK2_MAGE_P_NSE 0.001000000047497451 9
128 1 EK2_MAG_CAL 3 2
128 1 EK2_MAG_I_GATE 300 4
128 1 EK2_MAG_M_NSE 0.050000000745058060 9
128 1 EK2_MAX_FLOW 2.500000000000000000 9
128 1 EK2_NOAID_M_NSE 10.000000000000000000 9
128 1 EK2_POSNE_M_NSE 1.000000000000000000 9
128 1 EK2_POS_I_GATE 500 4
128 1 EK2_RNG_I_GATE 500 4
128 1 EK2_RNG_M_NSE 0.500000000000000000 9
128 1 EK2_TAU_OUTPUT 25 2
128 1 EK2_VELD_M_NSE 0.699999988079071045 9
128 1 EK2_VELNE_M_NSE 0.500000000000000000 9
128 1 EK2_VEL_I_GATE 500 4
128 1 EK2_WIND_PSCALE 0.500000000000000000 9
128 1 EK2_WIND_P_NSE 0.100000001490116119 9
128 1 EK2_YAW_I_GATE 300 4
128 1 EK2_YAW_M_NSE 0.500000000000000000 9
128 1 EKF_ENABLE 0 2
128 1 EPM_ENABLE 0 2
128 1 EPM_GRAB 1900 4
128 1 EPM_NEUTRAL 1500 4
128 1 EPM_REGRAB 0 2
128 1 EPM_RELEASE 1100 4
128 1 ESC_CALIBRATION 0 2
128 1 FENCE_ACTION 1 2
128 1 FENCE_ALT_MAX 100.000000000000000000 9
128 1 FENCE_DEPTH_MAX -10.000000000000000000 9
128 1 FENCE_ENABLE 0 2
128 1 FENCE_MARGIN 2.000000000000000000 9
128 1 FENCE_RADIUS 300.000000000000000000 9
128 1 FENCE_TOTAL 0 2
128 1 FENCE_TYPE 7 2
128 1 FLOW_ENABLE 0 2
128 1 FLOW_FXSCALER 0 4
128 1 FLOW_FYSCALER 0 4
128 1 FLOW_ORIENT_YAW 0 4
128 1 FLTMODE1 19 2
128 1 FLTMODE2 0 2
128 1 FLTMODE3 2 2
128 1 FLTMODE4 0 2
128 1 FLTMODE5 0 2
128 1 FLTMODE6 0 2
128 1 FRAME 1 2
128 1 FS_BATT_ENABLE 0 2
128 1 FS_BATT_MAH 0.000000000000000000 9
128 1 FS_BATT_VOLTAGE 10.500000000000000000 9
128 1 FS_CRASH_CHECK 0 2
128 1 FS_EKF_ACTION 1 2
128 1 FS_EKF_THRESH 0.800000011920928955 9
128 1 FS_GCS_ENABLE 1 2
128 1 FS_THR_ENABLE 0 2
128 1 FS_THR_VALUE 975 4
128 1 GCS_PID_MASK 0 4
128 1 GND_ABS_PRESS 100721.140625000000000000 9
128 1 GND_ALT_OFFSET 0.000000000000000000 9
128 1 GND_BASE_PRESS 98975.476562500000000000 9
128 1 GND_BASE_RESET 0 2
128 1 GND_PRIMARY 1 2
128 1 GND_SPEC_GRAV 1.000000000000000000 9
128 1 GND_TEMP 26.966283798217773438 9
128 1 GPS_AUTO_CONFIG 1 2
128 1 GPS_AUTO_SWITCH 1 2
128 1 GPS_GNSS_MODE 0 2
128 1 GPS_GNSS_MODE2 0 2
128 1 GPS_HDOP_GOOD 140 4
128 1 GPS_INJECT_TO 127 2
128 1 GPS_MIN_DGPS 100 2
128 1 GPS_MIN_ELEV 0 2
128 1 GPS_NAVFILTER 8 2
128 1 GPS_RAW_DATA 0 2
128 1 GPS_SAVE_CFG 0 2
128 1 GPS_SBAS_MODE 2 2
128 1 GPS_SBP_LOGMASK -256 4
128 1 GPS_TYPE 1 2
128 1 GPS_TYPE2 0 2
128 1 INS_ACC2OFFS_X 0.663968503475189209 9
128 1 INS_ACC2OFFS_Y 0.732862293720245361 9
128 1 INS_ACC2OFFS_Z 0.392130941152572632 9
128 1 INS_ACC2SCAL_X 1.044255375862121582 9
128 1 INS_ACC2SCAL_Y 1.021702170372009277 9
128 1 INS_ACC2SCAL_Z 1.012331962585449219 9
128 1 INS_ACC3OFFS_X 0.000000000000000000 9
128 1 INS_ACC3OFFS_Y 0.000000000000000000 9
128 1 INS_ACC3OFFS_Z 0.000000000000000000 9
128 1 INS_ACC3SCAL_X 0.000000000000000000 9
128 1 INS_ACC3SCAL_Y 0.000000000000000000 9
128 1 INS_ACC3SCAL_Z 0.000000000000000000 9
128 1 INS_ACCEL_FILTER 20 2
128 1 INS_ACCOFFS_X -0.093796379864215851 9
128 1 INS_ACCOFFS_Y -0.100834839046001434 9
128 1 INS_ACCOFFS_Z 0.410744011402130127 9
128 1 INS_ACCSCAL_X 0.995854496955871582 9
128 1 INS_ACCSCAL_Y 1.006878376007080078 9
128 1 INS_ACCSCAL_Z 0.992123425006866455 9
128 1 INS_ACC_BODYFIX 2 2
128 1 INS_GYR2OFFS_X 0.027385253459215164 9
128 1 INS_GYR2OFFS_Y 0.030301291495561600 9
128 1 INS_GYR2OFFS_Z -0.016768395900726318 9
128 1 INS_GYR3OFFS_X 0.000000000000000000 9
128 1 INS_GYR3OFFS_Y 0.000000000000000000 9
128 1 INS_GYR3OFFS_Z 0.000000000000000000 9
128 1 INS_GYROFFS_X 0.015457602217793465 9
128 1 INS_GYROFFS_Y 0.038951616734266281 9
128 1 INS_GYROFFS_Z -0.008368885144591331 9
128 1 INS_GYRO_FILTER 20 2
128 1 INS_GYR_CAL 1 2
128 1 INS_PRODUCT_ID 5 4
128 1 INS_STILL_THRESH 0.100000001490116119 9
128 1 INS_TRIM_OPTION 1 2
128 1 INS_USE 1 2
128 1 INS_USE2 1 2
128 1 INS_USE3 0 2
128 1 LAND_REPOSITION 1 2
128 1 LAND_SPEED 50 4
128 1 LAND_SPEED_HIGH 0 4
128 1 LGR_SERVO_DEPLOY 1750 4
128 1 LGR_SERVO_RTRACT 1250 4
128 1 LOG_BACKEND_TYPE 1 2
128 1 LOG_BITMASK 176126 6
128 1 LOG_DISARMED 0 2
128 1 LOG_FILE_BUFSIZE 16 2
128 1 LOG_REPLAY 0 2
128 1 MAG_ENABLE 1 2
128 1 MIS_RESTART 0 2
128 1 MIS_TOTAL 0 4
128 1 MNT_ANGMAX_PAN 4500 4
128 1 MNT_ANGMAX_ROL 4500 4
128 1 MNT_ANGMAX_TIL 4500 4
128 1 MNT_ANGMIN_PAN -4500 4
128 1 MNT_ANGMIN_ROL -4500 4
128 1 MNT_ANGMIN_TIL -4500 4
128 1 MNT_DEFLT_MODE 3 2
128 1 MNT_JSTICK_SPD 0 2
128 1 MNT_LEAD_PTCH 0.000000000000000000 9
128 1 MNT_LEAD_RLL 0.000000000000000000 9
128 1 MNT_NEUTRAL_X 0.000000000000000000 9
128 1 MNT_NEUTRAL_Y 0.000000000000000000 9
128 1 MNT_NEUTRAL_Z 0.000000000000000000 9
128 1 MNT_RC_IN_PAN 0 2
128 1 MNT_RC_IN_ROLL 0 2
128 1 MNT_RC_IN_TILT 8 2
128 1 MNT_RETRACT_X 0.000000000000000000 9
128 1 MNT_RETRACT_Y 0.000000000000000000 9
128 1 MNT_RETRACT_Z 0.000000000000000000 9
128 1 MNT_STAB_PAN 0 2
128 1 MNT_STAB_ROLL 0 2
128 1 MNT_STAB_TILT 0 2
128 1 MNT_TYPE 1 2
128 1 MOT_1_DIRECTION 0 2
128 1 MOT_2_DIRECTION 0 2
128 1 MOT_3_DIRECTION 1 2
128 1 MOT_4_DIRECTION 1 2
128 1 MOT_5_DIRECTION 0 2
128 1 MOT_6_DIRECTION 1 2
128 1 MOT_7_DIRECTION 1 2
128 1 MOT_8_DIRECTION 1 2
128 1 MOT_FV_CPLNG_K 1.000000000000000000 9
128 1 NTF_BUZZ_ENABLE 1 2
128 1 NTF_LED_BRIGHT 3 2
128 1 NTF_LED_OVERRIDE 0 2
128 1 PILOT_ACCEL_Z 50 4
128 1 PILOT_THR_BHV 0 4
128 1 PILOT_THR_FILT 0.000000000000000000 9
128 1 PILOT_TKOFF_ALT 0.000000000000000000 9
128 1 PILOT_TKOFF_DZ 100 4
128 1 PILOT_VELZ_MAX 50 4
128 1 POS_XY_P 1.000000000000000000 9
128 1 POS_Z_P 1.000000000000000000 9
128 1 PSC_ACC_XY_FILT 2.000000000000000000 9
128 1 RC10_DZ 0 4
128 1 RC10_FUNCTION 0 2
128 1 RC10_MAX 2000 4
128 1 RC10_MIN 1000 4
128 1 RC10_REV 1 2
128 1 RC10_TRIM 1500 4
128 1 RC11_DZ 0 4
128 1 RC11_FUNCTION 0 2
128 1 RC11_MAX 2000 4
128 1 RC11_MIN 1000 4
128 1 RC11_REV 1 2
128 1 RC11_TRIM 1500 4
128 1 RC12_DZ 0 4
128 1 RC12_FUNCTION 0 2
128 1 RC12_MAX 2000 4
128 1 RC12_MIN 1000 4
128 1 RC12_REV 1 2
128 1 RC12_TRIM 1500 4
128 1 RC13_DZ 0 4
128 1 RC13_FUNCTION 0 2
128 1 RC13_MAX 2000 4
128 1 RC13_MIN 1000 4
128 1 RC13_REV 1 2
128 1 RC13_TRIM 1500 4
128 1 RC14_DZ 0 4
128 1 RC14_FUNCTION 0 2
128 1 RC14_MAX 2000 4
128 1 RC14_MIN 1000 4
128 1 RC14_REV 1 2
128 1 RC14_TRIM 1500 4
128 1 RC1_DZ 30 4
128 1 RC1_MAX 2000 4
128 1 RC1_MIN 1000 4
128 1 RC1_REV 1 2
128 1 RC1_TRIM 1500 4
128 1 RC2_DZ 30 4
128 1 RC2_MAX 2000 4
128 1 RC2_MIN 1000 4
128 1 RC2_REV 1 2
128 1 RC2_TRIM 1500 4
128 1 RC3_DZ 30 4
128 1 RC3_MAX 1900 4
128 1 RC3_MIN 1100 4
128 1 RC3_REV 1 2
128 1 RC3_TRIM 1100 4
128 1 RC4_DZ 40 4
128 1 RC4_MAX 1900 4
128 1 RC4_MIN 1100 4
128 1 RC4_REV 1 2
128 1 RC4_TRIM 1500 4
128 1 RC5_DZ 0 4
128 1 RC5_FUNCTION 0 2
128 1 RC5_MAX 2000 4
128 1 RC5_MIN 1000 4
128 1 RC5_REV 1 2
128 1 RC5_TRIM 1500 4
128 1 RC6_DZ 30 4
128 1 RC6_FUNCTION 0 2
128 1 RC6_MAX 1900 4
128 1 RC6_MIN 1100 4
128 1 RC6_REV 1 2
128 1 RC6_TRIM 1500 4
128 1 RC7_DZ 30 4
128 1 RC7_FUNCTION 59 2
128 1 RC7_MAX 1900 4
128 1 RC7_MIN 1100 4
128 1 RC7_REV 0 2
128 1 RC7_TRIM 1500 4
128 1 RC8_DZ 0 4
128 1 RC8_FUNCTION 7 2
128 1 RC8_MAX 2000 4
128 1 RC8_MIN 1000 4
128 1 RC8_REV 0 2
128 1 RC8_TRIM 1500 4
128 1 RC9_DZ 0 4
128 1 RC9_FUNCTION 0 2
128 1 RC9_MAX 2000 4
128 1 RC9_MIN 1000 4
128 1 RC9_REV 1 2
128 1 RC9_TRIM 1500 4
128 1 RCMAP_FORWARD 6 2
128 1 RCMAP_LATERAL 7 2
128 1 RCMAP_PITCH 1 2
128 1 RCMAP_ROLL 2 2
128 1 RCMAP_THROTTLE 3 2
128 1 RCMAP_YAW 4 2
128 1 RC_FEEL_RP 50 2
128 1 RC_SPEED 490 4
128 1 RELAY_DEFAULT 0 2
128 1 RELAY_PIN 54 2
128 1 RELAY_PIN2 55 2
128 1 RELAY_PIN3 0 2
128 1 RELAY_PIN4 0 2
128 1 RNGFND2_ADDR 0 2
128 1 RNGFND2_FUNCTION 0 2
128 1 RNGFND2_GNDCLEAR 10 2
128 1 RNGFND2_MAX_CM 700 4
128 1 RNGFND2_MIN_CM 20 4
128 1 RNGFND2_OFFSET 0.000000000000000000 9
128 1 RNGFND2_PIN 0 2
128 1 RNGFND2_RMETRIC 1 2
128 1 RNGFND2_SCALING 3.000000000000000000 9
128 1 RNGFND2_SETTLE 0 4
128 1 RNGFND2_STOP_PIN 0 2
128 1 RNGFND2_TYPE 0 2
128 1 RNGFND_ADDR 0 2
128 1 RNGFND_FUNCTION 0 2
128 1 RNGFND_GAIN 0.800000011920928955 9
128 1 RNGFND_GNDCLEAR 10 2
128 1 RNGFND_MAX_CM 700 4
128 1 RNGFND_MIN_CM 20 4
128 1 RNGFND_OFFSET 0.000000000000000000 9
128 1 RNGFND_PIN 0 2
128 1 RNGFND_PWRRNG 0 4
128 1 RNGFND_RMETRIC 1 2
128 1 RNGFND_SCALING 3.000000000000000000 9
128 1 RNGFND_SETTLE 0 4
128 1 RNGFND_STOP_PIN 0 2
128 1 RNGFND_TYPE 0 2
128 1 RPM2_SCALING 1.000000000000000000 9
128 1 RPM2_TYPE 0 2
128 1 RPM_MAX 100000.000000000000000000 9
128 1 RPM_MIN 10.000000000000000000 9
128 1 RPM_MIN_QUAL 0.500000000000000000 9
128 1 RPM_SCALING 1.000000000000000000 9
128 1 RPM_TYPE 0 2
128 1 RSSI_ANA_PIN 0 2
128 1 RSSI_CHANNEL 0 2
128 1 RSSI_CHAN_HIGH 2000 4
128 1 RSSI_CHAN_LOW 1000 4
128 1 RSSI_PIN_HIGH 5.000000000000000000 9
128 1 RSSI_PIN_LOW 0.000000000000000000 9
128 1 RSSI_TYPE 0 2
128 1 RTL_ALT 1500 4
128 1 RTL_ALT_FINAL 0 4
128 1 RTL_CLIMB_MIN 0 4
128 1 RTL_CONE_SLOPE 3.000000000000000000 9
128 1 RTL_LOIT_TIME 5000 6
128 1 RTL_SPEED 0 4
128 1 SCHED_DEBUG 0 2
128 1 SCHED_LOOP_RATE 400 4
128 1 SERIAL0_BAUD 115 6
128 1 SERIAL0_PROTOCOL 1 2
128 1 SERIAL1_BAUD 57 6
128 1 SERIAL1_PROTOCOL 1 2
128 1 SERIAL2_BAUD 57 6
128 1 SERIAL2_PROTOCOL 1 2
128 1 SERIAL3_BAUD 38 6
128 1 SERIAL3_PROTOCOL 5 2
128 1 SERIAL4_BAUD 38 6
128 1 SERIAL4_PROTOCOL 5 2
128 1 SERIAL5_BAUD 57 6
128 1 SERIAL5_PROTOCOL 0 2
128 1 SIMPLE 0 2
128 1 SR0_ADSB 5 4
128 1 SR0_EXTRA1 4 4
128 1 SR0_EXTRA2 4 4
128 1 SR0_EXTRA3 4 4
128 1 SR0_EXT_STAT 4 4
128 1 SR0_PARAMS 10 4
128 1 SR0_POSITION 4 4
128 1 SR0_RAW_CTRL 4 4
128 1 SR0_RAW_SENS 4 4
128 1 SR0_RC_CHAN 4 4
128 1 SR1_ADSB 5 4
128 1 SR1_EXTRA1 0 4
128 1 SR1_EXTRA2 0 4
128 1 SR1_EXTRA3 0 4
128 1 SR1_EXT_STAT 0 4
128 1 SR1_PARAMS 0 4
128 1 SR1_POSITION 0 4
128 1 SR1_RAW_CTRL 0 4
128 1 SR1_RAW_SENS 0 4
128 1 SR1_RC_CHAN 0 4
128 1 SR2_ADSB 5 4
128 1 SR2_EXTRA1 0 4
128 1 SR2_EXTRA2 0 4
128 1 SR2_EXTRA3 0 4
128 1 SR2_EXT_STAT 0 4
128 1 SR2_PARAMS 0 4
128 1 SR2_POSITION 0 4
128 1 SR2_RAW_CTRL 0 4
128 1 SR2_RAW_SENS 0 4
128 1 SR2_RC_CHAN 0 4
128 1 SR3_ADSB 5 4
128 1 SR3_EXTRA1 0 4
128 1 SR3_EXTRA2 0 4
128 1 SR3_EXTRA3 0 4
128 1 SR3_EXT_STAT 0 4
128 1 SR3_PARAMS 0 4
128 1 SR3_POSITION 0 4
128 1 SR3_RAW_CTRL 0 4
128 1 SR3_RAW_SENS 0 4
128 1 SR3_RC_CHAN 0 4
128 1 SUPER_SIMPLE 0 2
128 1 SURFACE_DEPTH -10.000000000000000000 9
128 1 SYSID_MYGCS 255 4
128 1 SYSID_SW_MREV 120 4
128 1 SYSID_SW_TYPE 10 2
128 1 SYSID_THISMAV 1 4
128 1 TELEM_DELAY 0 2
128 1 TERRAIN_FOLLOW 0 2
128 1 THROW_MOT_START 0 2
128 1 THR_DZ 100 4
128 1 TUNE 0 2
128 1 TUNE_HIGH 1000 4
128 1 TUNE_LOW 0 4
128 1 VEL_XY_FILT_HZ 5.000000000000000000 9
128 1 VEL_XY_I 0.500000000000000000 9
128 1 VEL_XY_IMAX 1000.000000000000000000 9
128 1 VEL_XY_P 1.000000000000000000 9
128 1 VEL_Z_P 5.000000000000000000 9
128 1 WPNAV_ACCEL 100.000000000000000000 9
128 1 WPNAV_ACCEL_Z 100.000000000000000000 9
128 1 WPNAV_LOIT_JERK 1000.000000000000000000 9
128 1 WPNAV_LOIT_MAXA 250.000000000000000000 9
128 1 WPNAV_LOIT_MINA 25.000000000000000000 9
128 1 WPNAV_LOIT_SPEED 500.000000000000000000 9
128 1 WPNAV_RADIUS 200.000000000000000000 9
128 1 WPNAV_SPEED 500.000000000000000000 9
128 1 WPNAV_SPEED_DN 150.000000000000000000 9
128 1 WPNAV_SPEED_UP 250.000000000000000000 9
128 1 WP_TKOFF_NAV_ALT 0.000000000000000000 9
128 1 WP_YAW_BEHAVIOR 2 2
src/comm/MockLink.cc
View file @
2ed50262
...
...
@@ -180,6 +180,8 @@ void MockLink::_loadParams(void)
if
(
_firmwareType
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
if
(
_vehicleType
==
MAV_TYPE_FIXED_WING
)
{
paramFile
.
setFileName
(
":/unittest/APMArduPlaneMockLink.params"
);
}
else
if
(
_vehicleType
==
MAV_TYPE_SUBMARINE
)
{
paramFile
.
setFileName
(
":/unittest/APMArduSubMockLink.params"
);
}
else
{
paramFile
.
setFileName
(
":/unittest/APMArduCopterMockLink.params"
);
}
...
...
@@ -1030,6 +1032,18 @@ MockLink* MockLink::startAPMArduPlaneMockLink(bool sendStatusText, MockConfigur
return
_startMockLink
(
mockConfig
);
}
MockLink
*
MockLink
::
startAPMArduSubMockLink
(
bool
sendStatusText
,
MockConfiguration
::
FailureMode_t
failureMode
)
{
MockConfiguration
*
mockConfig
=
new
MockConfiguration
(
"APM ArduSub MockLink"
);
mockConfig
->
setFirmwareType
(
MAV_AUTOPILOT_ARDUPILOTMEGA
);
mockConfig
->
setVehicleType
(
MAV_TYPE_SUBMARINE
);
mockConfig
->
setSendStatusText
(
sendStatusText
);
mockConfig
->
setFailureMode
(
failureMode
);
return
_startMockLink
(
mockConfig
);
}
void
MockLink
::
_sendRCChannels
(
void
)
{
mavlink_message_t
msg
;
...
...
src/comm/MockLink.h
View file @
2ed50262
...
...
@@ -148,6 +148,7 @@ public:
static
MockLink
*
startGenericMockLink
(
bool
sendStatusText
,
MockConfiguration
::
FailureMode_t
failureMode
=
MockConfiguration
::
FailNone
);
static
MockLink
*
startAPMArduCopterMockLink
(
bool
sendStatusText
,
MockConfiguration
::
FailureMode_t
failureMode
=
MockConfiguration
::
FailNone
);
static
MockLink
*
startAPMArduPlaneMockLink
(
bool
sendStatusText
,
MockConfiguration
::
FailureMode_t
failureMode
=
MockConfiguration
::
FailNone
);
static
MockLink
*
startAPMArduSubMockLink
(
bool
sendStatusText
,
MockConfiguration
::
FailureMode_t
failureMode
=
MockConfiguration
::
FailNone
);
private
slots
:
virtual
void
_writeBytes
(
const
QByteArray
bytes
);
...
...
src/ui/preferences/MockLink.qml
View file @
2ed50262
...
...
@@ -48,6 +48,10 @@ Rectangle {
text
:
qsTr
(
"
APM ArduPlane Vehicle
"
)
onClicked
:
QGroundControl
.
startAPMArduPlaneMockLink
(
sendStatusText
.
checked
)
}
QGCButton
{
text
:
qsTr
(
"
APM ArduSub Vehicle
"
)
onClicked
:
QGroundControl
.
startAPMArduSubMockLink
(
sendStatusText
.
checked
)
}
QGCButton
{
text
:
qsTr
(
"
Generic Vehicle
"
)
onClicked
:
QGroundControl
.
startGenericMockLink
(
sendStatusText
.
checked
)
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment